move_group_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 
43 #include <sstream>
44 #include <string>
45 
46 void move_group::MoveGroupCapability::setContext(const MoveGroupContextPtr& context)
47 {
48  context_ = context;
49 }
50 
51 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
52  moveit_msgs::RobotState& first_state_msg,
53  std::vector<moveit_msgs::RobotTrajectory>& trajectory_msg) const
54 {
55  if (!trajectory.empty())
56  {
57  bool first = true;
58  trajectory_msg.resize(trajectory.size());
59  for (std::size_t i = 0; i < trajectory.size(); ++i)
60  {
61  if (trajectory[i].trajectory_)
62  {
63  if (first && !trajectory[i].trajectory_->empty())
64  {
65  moveit::core::robotStateToRobotStateMsg(trajectory[i].trajectory_->getFirstWayPoint(), first_state_msg);
66  first = false;
67  }
68  trajectory[i].trajectory_->getRobotTrajectoryMsg(trajectory_msg[i]);
69  }
70  }
71  }
72 }
73 
74 void move_group::MoveGroupCapability::convertToMsg(const robot_trajectory::RobotTrajectoryPtr& trajectory,
75  moveit_msgs::RobotState& first_state_msg,
76  moveit_msgs::RobotTrajectory& trajectory_msg) const
77 {
78  if (trajectory && !trajectory->empty())
79  {
80  moveit::core::robotStateToRobotStateMsg(trajectory->getFirstWayPoint(), first_state_msg);
81  trajectory->getRobotTrajectoryMsg(trajectory_msg);
82  }
83 }
84 
85 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
86  moveit_msgs::RobotState& first_state_msg,
87  moveit_msgs::RobotTrajectory& trajectory_msg) const
88 {
89  if (trajectory.size() > 1)
90  ROS_ERROR_STREAM("Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
91  if (!trajectory.empty())
92  convertToMsg(trajectory[0].trajectory_, first_state_msg, trajectory_msg);
93 }
94 
97 {
99  r.start_state = moveit_msgs::RobotState();
100  r.start_state.is_diff = true;
101  ROS_WARN("Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
102  "start state in the motion planning request");
103  return r;
104 }
105 
106 moveit_msgs::PlanningScene
107 move_group::MoveGroupCapability::clearSceneRobotState(const moveit_msgs::PlanningScene& scene) const
108 {
109  moveit_msgs::PlanningScene r = scene;
110  r.robot_state = moveit_msgs::RobotState();
111  r.robot_state.is_diff = true;
112  ROS_WARN("Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
113  "difference in the planning scene diff");
114  return r;
115 }
116 
117 std::string move_group::MoveGroupCapability::getActionResultString(const moveit_msgs::MoveItErrorCodes& error_code,
118  bool planned_trajectory_empty, bool plan_only)
119 {
120  switch (error_code.val)
121  {
122  case moveit_msgs::MoveItErrorCodes::SUCCESS:
123  if (planned_trajectory_empty)
124  return "Requested path and goal constraints are already met.";
125  else
126  {
127  if (plan_only)
128  return "Motion plan was computed succesfully.";
129  else
130  return "Solution was found and executed.";
131  }
132  case moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME:
133  return "Invalid group in motion plan request";
134  case moveit_msgs::MoveItErrorCodes::PLANNING_FAILED:
135  case moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN:
136  if (planned_trajectory_empty)
137  return "No motion plan found. No execution attempted.";
138  else
139  return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
140  case moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA:
141  return "Motion plan was found but it seems to be too costly and looking around did not help.";
142  case moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE:
143  return "Solution found but the environment changed during execution and the path was aborted";
144  default:
145  return moveit::core::MoveItErrorCode::toString(error_code);
146  }
147 }
148 
150 {
151  switch (state)
152  {
153  case IDLE:
154  return "IDLE";
155  case PLANNING:
156  return "PLANNING";
157  case MONITOR:
158  return "MONITOR";
159  case LOOK:
160  return "LOOK";
161  default:
162  return "UNKNOWN";
163  }
164 }
165 
166 bool move_group::MoveGroupCapability::performTransform(geometry_msgs::PoseStamped& pose_msg,
167  const std::string& target_frame) const
168 {
169  if (!context_ || !context_->planning_scene_monitor_->getTFClient())
170  return false;
171  if (pose_msg.header.frame_id == target_frame)
172  return true;
173  if (pose_msg.header.frame_id.empty())
174  {
175  pose_msg.header.frame_id = target_frame;
176  return true;
177  }
178 
179  try
180  {
181  geometry_msgs::TransformStamped common_tf = context_->planning_scene_monitor_->getTFClient()->lookupTransform(
182  pose_msg.header.frame_id, target_frame, ros::Time(0.0));
183  geometry_msgs::PoseStamped pose_msg_in(pose_msg);
184  pose_msg_in.header.stamp = common_tf.header.stamp;
185  context_->planning_scene_monitor_->getTFClient()->transform(pose_msg_in, pose_msg, target_frame);
186  }
187  catch (tf2::TransformException& ex)
188  {
189  ROS_ERROR("TF Problem: %s", ex.what());
190  return false;
191  }
192  return true;
193 }
194 
195 planning_pipeline::PlanningPipelinePtr
196 move_group::MoveGroupCapability::resolvePlanningPipeline(const std::string& pipeline_id) const
197 {
198  if (pipeline_id.empty())
199  {
200  // Without specified planning pipeline we use the default
201  return context_->planning_pipeline_;
202  }
203  else
204  {
205  // Attempt to get the planning pipeline for the specified identifier
206  try
207  {
208  auto pipeline = context_->moveit_cpp_->getPlanningPipelines().at(pipeline_id);
209  ROS_INFO_NAMED(getName(), "Using planning pipeline '%s'", pipeline_id.c_str());
210  return pipeline;
211  }
212  catch (const std::out_of_range&)
213  {
214  ROS_WARN_NAMED(getName(), "Couldn't find requested planning pipeline '%s'", pipeline_id.c_str());
215  }
216  }
217 
218  return planning_pipeline::PlanningPipelinePtr();
219 }
move_group::MoveGroupState
MoveGroupState
Definition: move_group_capability.h:79
move_group::MoveGroupCapability::performTransform
bool performTransform(geometry_msgs::PoseStamped &pose_msg, const std::string &target_frame) const
Definition: move_group_capability.cpp:166
move_group::LOOK
@ LOOK
Definition: move_group_capability.h:116
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
move_group::IDLE
@ IDLE
Definition: move_group_capability.h:113
move_group::MoveGroupCapability::context_
MoveGroupContextPtr context_
Definition: move_group_capability.h:132
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
moveit::core::MoveItErrorCode::toString
static const char * toString(const moveit_msgs::MoveItErrorCodes &error_code)
move_group::MoveGroupCapability::setContext
void setContext(const MoveGroupContextPtr &context)
Definition: move_group_capability.cpp:46
move_group_capability.h
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
move_group::MoveGroupCapability::resolvePlanningPipeline
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
Definition: move_group_capability.cpp:196
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
r
S r
move_group::MONITOR
@ MONITOR
Definition: move_group_capability.h:115
ros::Time
move_group::MoveGroupCapability::convertToMsg
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, std::vector< moveit_msgs::RobotTrajectory > &trajectory_msg) const
Definition: move_group_capability.cpp:51
move_group::MoveGroupCapability::getActionResultString
std::string getActionResultString(const moveit_msgs::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
Definition: move_group_capability.cpp:117
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
move_group::MoveGroupCapability::stateToStr
std::string stateToStr(MoveGroupState state) const
Definition: move_group_capability.cpp:149
tf2_geometry_msgs.h
conversions.h
move_group::MoveGroupCapability::clearRequestStartState
planning_interface::MotionPlanRequest clearRequestStartState(const planning_interface::MotionPlanRequest &request) const
Definition: move_group_capability.cpp:96
move_group::MoveGroupCapability::clearSceneRobotState
moveit_msgs::PlanningScene clearSceneRobotState(const moveit_msgs::PlanningScene &scene) const
Definition: move_group_capability.cpp:107
tf2::TransformException
moveit_cpp.h
move_group::PLANNING
@ PLANNING
Definition: move_group_capability.h:114
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_error_code.h


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:44