Skip to content

Commit

Permalink
remove use_joint_limits
Browse files Browse the repository at this point in the history
  • Loading branch information
Michael Wiznitzer committed Dec 26, 2022
1 parent e86f6ae commit adb0d55
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 24 deletions.
15 changes: 4 additions & 11 deletions core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,21 +116,14 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
result->addSuffixWayPoint(waypoint, 0.0);

auto timing = props.get<TimeParameterizationPtr>("time_parameterization");

if (joint_limits.size() > 0)
timing->computeTimeStamps(*result, joint_limits);
else
timing->computeTimeStamps(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
timing->computeTimeStamps(*result, joint_limits, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));

// smoothing
if (apply_ruckig_smoothing) {
trajectory_processing::RuckigSmoothing ruckig_smoothing;
if (joint_limits.size() > 0)
ruckig_smoothing.applySmoothing(*result, joint_limits);
else
ruckig_smoothing.applySmoothing(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
ruckig_smoothing.applySmoothing(*result, joint_limits, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
}

return achieved_fraction >= props.get<double>("min_fraction");
Expand Down
15 changes: 4 additions & 11 deletions core/src/solvers/joint_interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,21 +97,14 @@ bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr
return false;

auto timing = props.get<TimeParameterizationPtr>("time_parameterization");

if (joint_limits.size() > 0)
timing->computeTimeStamps(*result, joint_limits);
else
timing->computeTimeStamps(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
timing->computeTimeStamps(*result, joint_limits, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));

// smoothing
if (apply_ruckig_smoothing) {
trajectory_processing::RuckigSmoothing ruckig_smoothing;
if (joint_limits.size() > 0)
ruckig_smoothing.applySmoothing(*result, joint_limits);
else
ruckig_smoothing.applySmoothing(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
ruckig_smoothing.applySmoothing(*result, joint_limits, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
}

return true;
Expand Down
2 changes: 0 additions & 2 deletions core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,6 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
req.path_constraints = path_constraints;

req.joint_limits = joint_limits;
req.use_joint_limits = joint_limits.size() > 0;

req.skip_smoothing = !apply_ruckig_smoothing;

Expand Down Expand Up @@ -213,7 +212,6 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from, co
req.path_constraints = path_constraints;

req.joint_limits = joint_limits;
req.use_joint_limits = joint_limits.size() > 0;

req.skip_smoothing = !apply_ruckig_smoothing;

Expand Down

0 comments on commit adb0d55

Please sign in to comment.