46 #include <moveit_msgs/DisplayTrajectory.h>
79 moveit_msgs::GetCartesianPath::Response& res)
82 context_->planning_scene_monitor_->updateFrameTransforms();
89 std::string link_name = req.link_name;
90 if (link_name.empty() && !jmg->getLinkModelNames().empty())
91 link_name = jmg->getLinkModelNames().back();
95 const std::string& default_frame =
context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
96 bool no_transform = req.header.frame_id.empty() ||
100 for (std::size_t i = 0; i < req.waypoints.size(); ++i)
106 geometry_msgs::PoseStamped p;
107 p.header = req.header;
108 p.pose = req.waypoints[i];
113 ROS_ERROR_NAMED(
getName(),
"Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
122 if (req.max_step < std::numeric_limits<double>::epsilon())
125 "was not specified (this value needs to be > 0)");
126 res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
130 if (!waypoints.empty())
133 std::unique_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
134 std::unique_ptr<kinematic_constraints::KinematicConstraintSet> kset;
137 ls = std::make_unique<planning_scene_monitor::LockedPlanningSceneRO>(
context_->planning_scene_monitor_);
138 kset = std::make_unique<kinematic_constraints::KinematicConstraintSet>((*ls)->getRobotModel());
139 kset->add(req.path_constraints, (*ls)->getTransforms());
140 constraint_fn = [scene = req.avoid_collisions ?
141 static_cast<const planning_scene::PlanningSceneConstPtr&
>(*ls).get() :
145 const double* joint_group_variable_values) {
146 return isStateValid(scene, kset_ptr, robot_state, joint_group, joint_group_variable_values);
153 const Eigen::Isometry3d frame_pose = start_state.
getFrameInfo(link_name, link_model, found);
157 res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
160 "Attempting to follow %u waypoints for link '%s' using a step of %lf m "
161 "(in %s reference frame)",
162 (
unsigned int)waypoints.size(), link_name.c_str(), req.max_step,
163 global_frame ?
"global" :
"link");
165 std::vector<moveit::core::RobotStatePtr> traj;
173 for (
const moveit::core::RobotStatePtr& traj_state : traj)
181 if (req.max_cartesian_speed > 0.0)
184 req.cartesian_speed_limited_link);
188 ROS_INFO_NAMED(
getName(),
"Computed Cartesian path with %u points (followed %lf%% of requested trajectory)",
189 (
unsigned int)traj.size(), res.fraction * 100.0);
192 moveit_msgs::DisplayTrajectory disp;
193 disp.model_id =
context_->planning_scene_monitor_->getRobotModel()->getName();
194 disp.trajectory.resize(1, res.solution);
199 res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
203 res.error_code.val = moveit_msgs::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
206 res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;