Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Set max cartesian end-effector speed in planning pipeline #277

Draft
wants to merge 4 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <moveit/task_constructor/task.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit/trajectory_processing/cartesian_speed.h>
#include <moveit_msgs/MotionPlanRequest.h>
#include <moveit/kinematic_constraints/utils.h>
#include <eigen_conversions/eigen_msg.h>
Expand Down Expand Up @@ -149,6 +150,8 @@ void initMotionPlanRequest(moveit_msgs::MotionPlanRequest& req, const PropertyMa
req.num_planning_attempts = p.get<uint>("num_planning_attempts");
req.max_velocity_scaling_factor = p.get<double>("max_velocity_scaling_factor");
req.max_acceleration_scaling_factor = p.get<double>("max_acceleration_scaling_factor");
req.max_cartesian_speed = p.get<double>("max_cartesian_speed");
req.cartesian_speed_end_effector_link = p.get<std::string>("cartesian_speed_end_effector_link");
req.workspace_parameters = p.get<moveit_msgs::WorkspaceParameters>("workspace_parameters");
}

Expand All @@ -168,6 +171,11 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
::planning_interface::MotionPlanResponse res;
bool success = planner_->generatePlan(from, req, res);
result = res.trajectory_;
// optionally compute timing to move the eef with constant speed
if (req.max_cartesian_speed > 0.0) {
trajectory_processing::setMaxCartesianEndEffectorSpeed(*result, req.max_cartesian_speed,
req.cartesian_speed_end_effector_link);
}
gautz marked this conversation as resolved.
Show resolved Hide resolved
return success;
}

Expand All @@ -192,6 +200,11 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from, co
::planning_interface::MotionPlanResponse res;
bool success = planner_->generatePlan(from, req, res);
result = res.trajectory_;
// optionally compute timing to move the eef with constant speed
if (req.max_cartesian_speed > 0.0) {
trajectory_processing::setMaxCartesianEndEffectorSpeed(*result, req.max_cartesian_speed,
req.cartesian_speed_end_effector_link);
}
return success;
}
} // namespace solvers
Expand Down
3 changes: 3 additions & 0 deletions core/src/solvers/planner_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@ PlannerInterface::PlannerInterface() {
auto& p = properties();
p.declare<double>("max_velocity_scaling_factor", 1.0, "scale down max velocity by this factor");
p.declare<double>("max_acceleration_scaling_factor", 1.0, "scale down max acceleration by this factor");
p.declare<double>("max_cartesian_speed", 0.0, "maximum cartesian end-effector speed");
p.declare<std::string>("cartesian_speed_end_effector_link", "end_effector_link",
"end-effector link with limited the velocity");
}
} // namespace solvers
} // namespace task_constructor
Expand Down