Skip to content

Commit

Permalink
Update trajectory_generator_lin.cpp
Browse files Browse the repository at this point in the history
setting eqradius = 0.0 and replacing the cartesianTrapVelocityProfile() function with cartesianRectVelocityProfile for generating the velocity profile of the KDL path
  • Loading branch information
vivekcdavid authored Oct 30, 2024
1 parent ed90f7a commit a35a3c9
Showing 1 changed file with 8 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -154,10 +154,12 @@ void TrajectoryGeneratorLIN::plan(const planning_scene::PlanningSceneConstPtr& s
// create Cartesian path for lin
std::unique_ptr<KDL::Path> path(setPathLIN(plan_info.start_pose, plan_info.goal_pose));

// create velocity profile
// create velocity profile using trap profile
//std::unique_ptr<KDL::VelocityProfile> vp(
// cartesianTrapVelocityProfile(req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor, path));
// create velocity profile using rect profile
std::unique_ptr<KDL::VelocityProfile> vp(
cartesianTrapVelocityProfile(req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor, path));

cartesianRectVelocityProfile(req.max_velocity_scaling_factor, path));
// combine path and velocity profile into Cartesian trajectory
// with the third parameter set to false, KDL::Trajectory_Segment does not
// take
Expand Down Expand Up @@ -185,8 +187,9 @@ std::unique_ptr<KDL::Path> TrajectoryGeneratorLIN::setPathLIN(const Eigen::Affin
KDL::Frame kdl_start_pose, kdl_goal_pose;
tf2::transformEigenToKDL(start_pose, kdl_start_pose);
tf2::transformEigenToKDL(goal_pose, kdl_goal_pose);
double eqradius = planner_limits_.getCartesianLimits().getMaxTranslationalVelocity() /
planner_limits_.getCartesianLimits().getMaxRotationalVelocity();
//double eqradius = planner_limits_.getCartesianLimits().getMaxTranslationalVelocity() /
// planner_limits_.getCartesianLimits().getMaxRotationalVelocity();
double eqradius = 0.0;
KDL::RotationalInterpolation* rot_interpo = new KDL::RotationalInterpolation_SingleAxis();

return std::unique_ptr<KDL::Path>(
Expand Down

0 comments on commit a35a3c9

Please sign in to comment.