Public Member Functions | Private Member Functions | Private Attributes | List of all members
move_group::MoveGroupMoveAction Class Reference

#include <move_action_capability.h>

Inheritance diagram for move_group::MoveGroupMoveAction:
Inheritance graph
[legend]

Public Member Functions

void initialize () override
 
 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 executeMoveCallbackPlanAndExecute (const moveit_msgs::MoveGroupGoalConstPtr &goal, moveit_msgs::MoveGroupResult &action_res)
 
void executeMoveCallbackPlanOnly (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 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
 
void convertToMsg (const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::RobotState &first_state_msg, std::vector< 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
 
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline (const std::string &pipeline_id) 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_
 

Detailed Description

Definition at line 78 of file move_action_capability.h.

Constructor & Destructor Documentation

◆ MoveGroupMoveAction()

move_group::MoveGroupMoveAction::MoveGroupMoveAction ( )

Definition at line 81 of file move_action_capability.cpp.

Member Function Documentation

◆ executeMoveCallback()

void move_group::MoveGroupMoveAction::executeMoveCallback ( const moveit_msgs::MoveGroupGoalConstPtr &  goal)
private

Definition at line 95 of file move_action_capability.cpp.

◆ executeMoveCallbackPlanAndExecute()

void move_group::MoveGroupMoveAction::executeMoveCallbackPlanAndExecute ( const moveit_msgs::MoveGroupGoalConstPtr &  goal,
moveit_msgs::MoveGroupResult &  action_res 
)
private

Definition at line 132 of file move_action_capability.cpp.

◆ executeMoveCallbackPlanOnly()

void move_group::MoveGroupMoveAction::executeMoveCallbackPlanOnly ( const moveit_msgs::MoveGroupGoalConstPtr &  goal,
moveit_msgs::MoveGroupResult &  action_res 
)
private

Definition at line 182 of file move_action_capability.cpp.

◆ initialize()

void move_group::MoveGroupMoveAction::initialize ( )
overridevirtual

Implements move_group::MoveGroupCapability.

Definition at line 86 of file move_action_capability.cpp.

◆ planUsingPlanningPipeline()

bool move_group::MoveGroupMoveAction::planUsingPlanningPipeline ( const planning_interface::MotionPlanRequest req,
plan_execution::ExecutableMotionPlan plan 
)
private

Definition at line 225 of file move_action_capability.cpp.

◆ preemptMoveCallback()

void move_group::MoveGroupMoveAction::preemptMoveCallback ( )
private

Definition at line 271 of file move_action_capability.cpp.

◆ setMoveState()

void move_group::MoveGroupMoveAction::setMoveState ( MoveGroupState  state)
private

Definition at line 277 of file move_action_capability.cpp.

◆ startMoveExecutionCallback()

void move_group::MoveGroupMoveAction::startMoveExecutionCallback ( )
private

Definition at line 261 of file move_action_capability.cpp.

◆ startMoveLookCallback()

void move_group::MoveGroupMoveAction::startMoveLookCallback ( )
private

Definition at line 266 of file move_action_capability.cpp.

Member Data Documentation

◆ move_action_server_

std::unique_ptr<actionlib::SimpleActionServer<moveit_msgs::MoveGroupAction> > move_group::MoveGroupMoveAction::move_action_server_
private

Definition at line 130 of file move_action_capability.h.

◆ move_feedback_

moveit_msgs::MoveGroupFeedback move_group::MoveGroupMoveAction::move_feedback_
private

Definition at line 131 of file move_action_capability.h.

◆ move_state_

MoveGroupState move_group::MoveGroupMoveAction::move_state_
private

Definition at line 133 of file move_action_capability.h.

◆ preempt_requested_

bool move_group::MoveGroupMoveAction::preempt_requested_
private

Definition at line 134 of file move_action_capability.h.


The documentation for this class was generated from the following files:


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