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

#include <execute_trajectory_action_capability.h>

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

Public Member Functions

void initialize () override
 
 MoveGroupExecuteTrajectoryAction ()
 
- 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 executePath (const moveit_msgs::ExecuteTrajectoryGoalConstPtr &goal, moveit_msgs::ExecuteTrajectoryResult &action_res)
 
void executePathCallback (const moveit_msgs::ExecuteTrajectoryGoalConstPtr &goal)
 
void preemptExecuteTrajectoryCallback ()
 
void setExecuteTrajectoryState (MoveGroupState state)
 

Private Attributes

std::unique_ptr< actionlib::SimpleActionServer< moveit_msgs::ExecuteTrajectoryAction > > execute_action_server_
 

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 82 of file execute_trajectory_action_capability.h.

Constructor & Destructor Documentation

◆ MoveGroupExecuteTrajectoryAction()

move_group::MoveGroupExecuteTrajectoryAction::MoveGroupExecuteTrajectoryAction ( )

Definition at line 78 of file execute_trajectory_action_capability.cpp.

Member Function Documentation

◆ executePath()

void move_group::MoveGroupExecuteTrajectoryAction::executePath ( const moveit_msgs::ExecuteTrajectoryGoalConstPtr &  goal,
moveit_msgs::ExecuteTrajectoryResult &  action_res 
)
private

Definition at line 121 of file execute_trajectory_action_capability.cpp.

◆ executePathCallback()

void move_group::MoveGroupExecuteTrajectoryAction::executePathCallback ( const moveit_msgs::ExecuteTrajectoryGoalConstPtr &  goal)
private

Definition at line 91 of file execute_trajectory_action_capability.cpp.

◆ initialize()

void move_group::MoveGroupExecuteTrajectoryAction::initialize ( )
overridevirtual

◆ preemptExecuteTrajectoryCallback()

void move_group::MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback ( )
private

Definition at line 156 of file execute_trajectory_action_capability.cpp.

◆ setExecuteTrajectoryState()

void move_group::MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState ( MoveGroupState  state)
private

Definition at line 161 of file execute_trajectory_action_capability.cpp.

Member Data Documentation

◆ execute_action_server_

std::unique_ptr<actionlib::SimpleActionServer<moveit_msgs::ExecuteTrajectoryAction> > move_group::MoveGroupExecuteTrajectoryAction::execute_action_server_
private

Definition at line 128 of file execute_trajectory_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