57 class MoveGroupCapability
 
   68   void setContext(
const MoveGroupContextPtr& context);
 
   72   const std::string& 
getName()
 const 
   78   std::string 
getActionResultString(
const moveit_msgs::MoveItErrorCodes& error_code, 
bool planned_trajectory_empty,
 
   82   void convertToMsg(
const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
 
   83                     moveit_msgs::RobotState& first_state_msg,
 
   84                     std::vector<moveit_msgs::RobotTrajectory>& trajectory_msg) 
const;
 
   85   void convertToMsg(
const robot_trajectory::RobotTrajectoryPtr& trajectory, moveit_msgs::RobotState& first_state_msg,
 
   86                     moveit_msgs::RobotTrajectory& trajectory_msg) 
const;
 
   87   void convertToMsg(
const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
 
   88                     moveit_msgs::RobotState& first_state_msg, moveit_msgs::RobotTrajectory& trajectory_msg) 
const;
 
   93   bool performTransform(geometry_msgs::PoseStamped& pose_msg, 
const std::string& target_frame) 
const;