68 void setContext(
const MoveGroupContextPtr& context);
78 std::string
getActionResultString(
const moveit_msgs::msg::MoveItErrorCodes& error_code,
bool planned_trajectory_empty,
82 void convertToMsg(
const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
83 moveit_msgs::msg::RobotState& first_state_msg,
84 std::vector<moveit_msgs::msg::RobotTrajectory>& trajectory_msg)
const;
85 void convertToMsg(
const robot_trajectory::RobotTrajectoryPtr& trajectory,
86 moveit_msgs::msg::RobotState& first_state_msg,
87 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const;
88 void convertToMsg(
const std::vector<plan_execution::ExecutableTrajectory>& trajectory,
89 moveit_msgs::msg::RobotState& first_state_msg,
90 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const;
94 moveit_msgs::msg::PlanningScene
clearSceneRobotState(
const moveit_msgs::msg::PlanningScene& scene)
const;
95 bool performTransform(geometry_msgs::msg::PoseStamped& pose_msg,
const std::string& target_frame)
const;