#include <move_action_capability.h>
Public Member Functions | |
virtual void | initialize () |
MoveGroupMoveAction () | |
Public Member Functions inherited from move_group::MoveGroupCapability | |
const std::string & | getName () const |
MoveGroupCapability (const std::string &capability_name) | |
void | setContext (const MoveGroupContextPtr &context) |
virtual | ~MoveGroupCapability () |
Private Member Functions | |
void | executeMoveCallback (const moveit_msgs::MoveGroupGoalConstPtr &goal) |
void | executeMoveCallback_PlanAndExecute (const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res) |
void | executeMoveCallback_PlanOnly (const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res) |
bool | planUsingPlanningPipeline (const planning_interface::MotionPlanRequest &req, plan_execution::ExecutableMotionPlan &plan) |
void | preemptMoveCallback () |
void | setMoveState (MoveGroupState state) |
void | startMoveExecutionCallback () |
void | startMoveLookCallback () |
Private Attributes | |
std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::MoveGroupAction > > | move_action_server_ |
moveit_msgs::MoveGroupFeedback | move_feedback_ |
MoveGroupState | move_state_ |
bool | preempt_requested_ |
Additional Inherited Members | |
Protected Member Functions inherited from move_group::MoveGroupCapability | |
planning_interface::MotionPlanRequest | clearRequestStartState (const planning_interface::MotionPlanRequest &request) const |
moveit_msgs::PlanningScene | clearSceneRobotState (const moveit_msgs::PlanningScene &scene) const |
void | convertToMsg (const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, std::vector< moveit_msgs::RobotTrajectory > &trajectory_msg) const |
void | convertToMsg (const robot_trajectory::RobotTrajectoryPtr &trajectory, moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const |
void | convertToMsg (const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const |
std::string | getActionResultString (const moveit_msgs::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only) |
bool | performTransform (geometry_msgs::PoseStamped &pose_msg, const std::string &target_frame) const |
std::string | stateToStr (MoveGroupState state) const |
Protected Attributes inherited from move_group::MoveGroupCapability | |
std::string | capability_name_ |
MoveGroupContextPtr | context_ |
ros::NodeHandle | node_handle_ |
ros::NodeHandle | root_node_handle_ |
Definition at line 47 of file move_action_capability.h.
move_group::MoveGroupMoveAction::MoveGroupMoveAction | ( | ) |
Definition at line 46 of file move_action_capability.cpp.
|
private |
Definition at line 60 of file move_action_capability.cpp.
|
private |
Definition at line 96 of file move_action_capability.cpp.
|
private |
Definition at line 160 of file move_action_capability.cpp.
|
virtual |
Implements move_group::MoveGroupCapability.
Definition at line 51 of file move_action_capability.cpp.
|
private |
Definition at line 197 of file move_action_capability.cpp.
|
private |
Definition at line 234 of file move_action_capability.cpp.
|
private |
Definition at line 240 of file move_action_capability.cpp.
|
private |
Definition at line 224 of file move_action_capability.cpp.
|
private |
Definition at line 229 of file move_action_capability.cpp.
|
private |
Definition at line 67 of file move_action_capability.h.
|
private |
Definition at line 68 of file move_action_capability.h.
|
private |
Definition at line 70 of file move_action_capability.h.
|
private |
Definition at line 71 of file move_action_capability.h.