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 all 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
5 changes: 5 additions & 0 deletions core/include/moveit/task_constructor/solvers/cartesian_path.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,11 @@ class CartesianPath : public PlannerInterface
void setMaxVelocityScaling(double factor) { setProperty("max_velocity_scaling_factor", factor); }
void setMaxAccelerationScaling(double factor) { setProperty("max_acceleration_scaling_factor", factor); }

void setMaxCartesianSpeed(double max) { setProperty("max_cartesian_speed", max); }
void setCartesianSpeedLimitedLink(std::string limited_link) {
setProperty("cartesian_speed_limited_link", limited_link);
}

void init(const moveit::core::RobotModelConstPtr& robot_model) override;

bool plan(const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to,
Expand Down
20 changes: 17 additions & 3 deletions core/src/solvers/cartesian_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <moveit/task_constructor/solvers/cartesian_path.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <moveit/trajectory_processing/cartesian_speed.h>
#if MOVEIT_MASTER
#include <moveit/robot_state/cartesian_interpolator.h>
#endif
Expand Down Expand Up @@ -105,9 +106,22 @@ bool CartesianPath::plan(const planning_scene::PlanningSceneConstPtr& from, cons
for (const auto& waypoint : trajectory)
result->addSuffixWayPoint(waypoint, 0.0);

trajectory_processing::IterativeParabolicTimeParameterization timing;
timing.computeTimeStamps(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
// optionally compute timing to move the eef with constant speed
if (props.get<double>("max_cartesian_speed") > 0.0) {
if (trajectory_processing::limitMaxCartesianLinkSpeed(
*result, props.get<double>("max_cartesian_speed"),
props.get<std::string>("cartesian_speed_limited_link"))) {
ROS_INFO_STREAM("successfully set max " << props.get<double>("max_cartesian_speed") << " [m/s] for link "
<< props.get<std::string>("cartesian_speed_limited_link"));
} else {
ROS_ERROR_STREAM("failed to set max speed for link_ "
<< props.get<std::string>("cartesian_speed_limited_link"));
}
} else {
trajectory_processing::IterativeParabolicTimeParameterization timing;
timing.computeTimeStamps(*result, props.get<double>("max_velocity_scaling_factor"),
props.get<double>("max_acceleration_scaling_factor"));
}
}

return achieved_fraction >= props.get<double>("min_fraction");
Expand Down
2 changes: 2 additions & 0 deletions core/src/solvers/pipeline_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,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.cartesian_speed_limited_link = p.get<std::string>("cartesian_speed_limited_link");
req.max_cartesian_speed = p.get<double>("max_cartesian_speed");
req.workspace_parameters = p.get<moveit_msgs::WorkspaceParameters>("workspace_parameters");
}

Expand Down
2 changes: 2 additions & 0 deletions core/src/solvers/planner_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ 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 speed");
p.declare<std::string>("cartesian_speed_limited_link", "", "link with limited cartesian speed");
}
} // namespace solvers
} // namespace task_constructor
Expand Down