#include <execute_task_solution_capability.h>
Public Member Functions | |
ExecuteTaskSolutionCapability () | |
void | initialize () override |
![]() | |
const std::string & | getName () const |
MoveGroupCapability (const std::string &capability_name) | |
void | setContext (const MoveGroupContextPtr &context) |
virtual | ~MoveGroupCapability () |
Private Member Functions | |
bool | constructMotionPlan (const moveit_task_constructor_msgs::Solution &solution, plan_execution::ExecutableMotionPlan &plan) |
void | execCallback (const moveit_task_constructor_msgs::ExecuteTaskSolutionGoalConstPtr &goal) |
void | preemptCallback () |
Private Attributes | |
std::unique_ptr< actionlib::SimpleActionServer< moveit_task_constructor_msgs::ExecuteTaskSolutionAction > > | as_ |
Additional Inherited Members | |
![]() | |
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 |
![]() | |
std::string | capability_name_ |
MoveGroupContextPtr | context_ |
ros::NodeHandle | node_handle_ |
ros::NodeHandle | root_node_handle_ |
Definition at line 85 of file execute_task_solution_capability.h.
move_group::ExecuteTaskSolutionCapability::ExecuteTaskSolutionCapability | ( | ) |
Definition at line 83 of file execute_task_solution_capability.cpp.
|
private |
Definition at line 127 of file execute_task_solution_capability.cpp.
|
private |
Definition at line 94 of file execute_task_solution_capability.cpp.
|
overridevirtual |
Implements move_group::MoveGroupCapability.
Definition at line 85 of file execute_task_solution_capability.cpp.
|
private |
Definition at line 122 of file execute_task_solution_capability.cpp.
|
private |
Definition at line 131 of file execute_task_solution_capability.h.