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

#include <tf_publisher_capability.h>

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

Public Member Functions

void initialize () override
 
 TfPublisher ()
 
 ~TfPublisher () override
 
- 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 publishPlanningSceneFrames ()
 

Private Attributes

bool keep_running_
 
std::string prefix_
 
int rate_
 
std::thread thread_
 

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 76 of file tf_publisher_capability.h.

Constructor & Destructor Documentation

◆ TfPublisher()

move_group::TfPublisher::TfPublisher ( )

Definition at line 79 of file tf_publisher_capability.cpp.

◆ ~TfPublisher()

move_group::TfPublisher::~TfPublisher ( )
override

Definition at line 83 of file tf_publisher_capability.cpp.

Member Function Documentation

◆ initialize()

void move_group::TfPublisher::initialize ( )
overridevirtual

Implements move_group::MoveGroupCapability.

Definition at line 154 of file tf_publisher_capability.cpp.

◆ publishPlanningSceneFrames()

void move_group::TfPublisher::publishPlanningSceneFrames ( )
private

Definition at line 106 of file tf_publisher_capability.cpp.

Member Data Documentation

◆ keep_running_

bool move_group::TfPublisher::keep_running_
private

Definition at line 121 of file tf_publisher_capability.h.

◆ prefix_

std::string move_group::TfPublisher::prefix_
private

Definition at line 119 of file tf_publisher_capability.h.

◆ rate_

int move_group::TfPublisher::rate_
private

Definition at line 118 of file tf_publisher_capability.h.

◆ thread_

std::thread move_group::TfPublisher::thread_
private

Definition at line 120 of file tf_publisher_capability.h.


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


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Mar 3 2024 03:24:41