moveit2
The MoveIt Motion Planning Framework for ROS 2.
cartesian_path_service_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
42 #include <tf2_eigen/tf2_eigen.hpp>
47 #include <moveit_msgs/msg/display_trajectory.hpp>
49 
50 namespace
51 {
52 bool isStateValid(const planning_scene::PlanningScene* planning_scene,
54  const moveit::core::JointModelGroup* group, const double* ik_solution)
55 {
56  state->setJointGroupPositions(group, ik_solution);
57  state->update();
58  return (!planning_scene || !planning_scene->isStateColliding(*state, group->getName())) &&
59  (!constraint_set || constraint_set->decide(*state).satisfied);
60 }
61 } // namespace
62 
63 namespace move_group
64 {
65 static const rclcpp::Logger LOGGER =
66  rclcpp::get_logger("moveit_move_group_default_capabilities.cartersian_path_service_capability");
67 
69  : MoveGroupCapability("CartesianPathService"), display_computed_paths_(true)
70 {
71 }
72 
74 {
75  display_path_ = context_->moveit_cpp_->getNode()->create_publisher<moveit_msgs::msg::DisplayTrajectory>(
77 
78  cartesian_path_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetCartesianPath>(
79 
80  CARTESIAN_PATH_SERVICE_NAME,
81  [this](const std::shared_ptr<rmw_request_id_t>& req_id,
82  const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
83  const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res) -> bool {
84  return computeService(req_id, req, res);
85  });
86 }
87 
88 bool MoveGroupCartesianPathService::computeService(
89  const std::shared_ptr<rmw_request_id_t>& /* unused */,
90  const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Request>& req,
91  const std::shared_ptr<moveit_msgs::srv::GetCartesianPath::Response>& res)
92 {
93  RCLCPP_INFO(LOGGER, "Received request to compute Cartesian path");
94  context_->planning_scene_monitor_->updateFrameTransforms();
95 
96  moveit::core::RobotState start_state =
97  planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)->getCurrentState();
98  moveit::core::robotStateMsgToRobotState(req->start_state, start_state);
99  if (const moveit::core::JointModelGroup* jmg = start_state.getJointModelGroup(req->group_name))
100  {
101  std::string link_name = req->link_name;
102  if (link_name.empty() && !jmg->getLinkModelNames().empty())
103  link_name = jmg->getLinkModelNames().back();
104 
105  bool ok = true;
106  EigenSTL::vector_Isometry3d waypoints(req->waypoints.size());
107  const std::string& default_frame = context_->planning_scene_monitor_->getRobotModel()->getModelFrame();
108  bool no_transform = req->header.frame_id.empty() ||
109  moveit::core::Transforms::sameFrame(req->header.frame_id, default_frame) ||
110  moveit::core::Transforms::sameFrame(req->header.frame_id, link_name);
111 
112  for (std::size_t i = 0; i < req->waypoints.size(); ++i)
113  {
114  if (no_transform)
115  tf2::fromMsg(req->waypoints[i], waypoints[i]);
116  else
117  {
118  geometry_msgs::msg::PoseStamped p;
119  p.header = req->header;
120  p.pose = req->waypoints[i];
121  if (performTransform(p, default_frame))
122  tf2::fromMsg(p.pose, waypoints[i]);
123  else
124  {
125  RCLCPP_ERROR(LOGGER, "Error encountered transforming waypoints to frame '%s'", default_frame.c_str());
126  ok = false;
127  break;
128  }
129  }
130  }
131 
132  if (ok)
133  {
134  if (req->max_step < std::numeric_limits<double>::epsilon())
135  {
136  RCLCPP_ERROR(LOGGER, "Maximum step to take between consecutive configurations along Cartesian path"
137  "was not specified (this value needs to be > 0)");
138  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
139  }
140  else
141  {
142  if (!waypoints.empty())
143  {
145  std::unique_ptr<planning_scene_monitor::LockedPlanningSceneRO> ls;
146  std::unique_ptr<kinematic_constraints::KinematicConstraintSet> kset;
147  if (req->avoid_collisions || !moveit::core::isEmpty(req->path_constraints))
148  {
149  ls = std::make_unique<planning_scene_monitor::LockedPlanningSceneRO>(context_->planning_scene_monitor_);
150  kset = std::make_unique<kinematic_constraints::KinematicConstraintSet>((*ls)->getRobotModel());
151  kset->add(req->path_constraints, (*ls)->getTransforms());
152  constraint_fn =
153  [scene = req->avoid_collisions ? static_cast<const planning_scene::PlanningSceneConstPtr&>(*ls).get() :
154  nullptr,
155  kset = kset->empty() ? nullptr : kset.get()](moveit::core::RobotState* robot_state,
156  const moveit::core::JointModelGroup* joint_group,
157  const double* joint_group_variable_values) {
158  return isStateValid(scene, kset, robot_state, joint_group, joint_group_variable_values);
159  };
160  }
161  bool global_frame = !moveit::core::Transforms::sameFrame(link_name, req->header.frame_id);
162  RCLCPP_INFO(LOGGER,
163  "Attempting to follow %u waypoints for link '%s' using a step of %lf m "
164  "and jump threshold %lf (in %s reference frame)",
165  (unsigned int)waypoints.size(), link_name.c_str(), req->max_step, req->jump_threshold,
166  global_frame ? "global" : "link");
167  std::vector<moveit::core::RobotStatePtr> traj;
169  &start_state, jmg, traj, start_state.getLinkModel(link_name), waypoints, global_frame,
170  moveit::core::MaxEEFStep(req->max_step), moveit::core::JumpThreshold(req->jump_threshold), constraint_fn);
171  moveit::core::robotStateToRobotStateMsg(start_state, res->start_state);
172 
173  robot_trajectory::RobotTrajectory rt(context_->planning_scene_monitor_->getRobotModel(), req->group_name);
174  for (const moveit::core::RobotStatePtr& traj_state : traj)
175  rt.addSuffixWayPoint(traj_state, 0.0);
176 
177  // time trajectory
178  // \todo optionally compute timing to move the eef with constant speed
180  time_param.computeTimeStamps(rt, 1.0);
181 
182  rt.getRobotTrajectoryMsg(res->solution);
183  RCLCPP_INFO(LOGGER, "Computed Cartesian path with %u points (followed %lf%% of requested trajectory)",
184  (unsigned int)traj.size(), res->fraction * 100.0);
185  if (display_computed_paths_ && rt.getWayPointCount() > 0)
186  {
187  moveit_msgs::msg::DisplayTrajectory disp;
188  disp.model_id = context_->planning_scene_monitor_->getRobotModel()->getName();
189  disp.trajectory.resize(1, res->solution);
190  moveit::core::robotStateToRobotStateMsg(rt.getFirstWayPoint(), disp.trajectory_start);
191  display_path_->publish(disp);
192  }
193  }
194  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
195  }
196  }
197  else
198  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FRAME_TRANSFORM_FAILURE;
199  }
200  else
201  res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
202 
203  return true;
204 }
205 
206 } // namespace move_group
207 
208 #include <pluginlib/class_list_macros.hpp>
209 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
A class that contains many different constraints, and can check RobotState *versus the full set....
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
Determines whether all constraints are satisfied by state, returning a single evaluation result.
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:122
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void update(bool force=false)
Update all transforms.
static bool sameFrame(const std::string &frame1, const std::string &frame2)
Check if two frames end up being the same once the missing / are added as prefix (if they are missing...
Definition: transforms.cpp:64
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
This class maintains the representation of the environment as seen by a planning instance....
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Maintain a sequence of waypoints and the time durations between these waypoints.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
scene
Definition: pick.py:52
p
Definition: pick.py:62
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
bool satisfied
Whether or not the constraint or constraints were satisfied.
Struct for containing jump_threshold.
Struct for containing max_step for computeCartesianPath.