Classes | |
struct | ClientGoalInfo |
Public Member Functions | |
void | cancelCB (GoalHandle &gh) |
const std::string | cleanTfFrame (const std::string frame_id) const |
void | goalCB (GoalHandle &gh) |
void | processGoal (boost::shared_ptr< ClientGoalInfo > goal_info, const ros::TimerEvent &) |
TFRepublisher (const std::string &name) | |
~TFRepublisher () | |
Protected Types | |
typedef TFTransformServer::GoalHandle | GoalHandle |
typedef actionlib::ActionServer < tf2_web_republisher::TFSubscriptionAction > | TFTransformServer |
Protected Attributes | |
std::list< boost::shared_ptr < ClientGoalInfo > > | active_goals_ |
TFTransformServer | as_ |
unsigned int | client_ID_count_ |
boost::mutex | goals_mutex_ |
ros::NodeHandle | nh_ |
tf2::Buffer | tf_buffer_ |
boost::mutex | tf_buffer_mutex_ |
tf2::TransformListener | tf_listener_ |
Definition at line 52 of file tf_web_republisher.cpp.
typedef TFTransformServer::GoalHandle TFRepublisher::GoalHandle [protected] |
Definition at line 57 of file tf_web_republisher.cpp.
typedef actionlib::ActionServer<tf2_web_republisher::TFSubscriptionAction> TFRepublisher::TFTransformServer [protected] |
Definition at line 56 of file tf_web_republisher.cpp.
TFRepublisher::TFRepublisher | ( | const std::string & | name | ) | [inline] |
Definition at line 89 of file tf_web_republisher.cpp.
TFRepublisher::~TFRepublisher | ( | ) | [inline] |
Definition at line 101 of file tf_web_republisher.cpp.
void TFRepublisher::cancelCB | ( | GoalHandle & | gh | ) | [inline] |
Definition at line 103 of file tf_web_republisher.cpp.
const std::string TFRepublisher::cleanTfFrame | ( | const std::string | frame_id | ) | const [inline] |
Definition at line 125 of file tf_web_republisher.cpp.
void TFRepublisher::goalCB | ( | GoalHandle & | gh | ) | [inline] |
Definition at line 133 of file tf_web_republisher.cpp.
void TFRepublisher::processGoal | ( | boost::shared_ptr< ClientGoalInfo > | goal_info, |
const ros::TimerEvent & | |||
) | [inline] |
Definition at line 174 of file tf_web_republisher.cpp.
std::list<boost::shared_ptr<ClientGoalInfo> > TFRepublisher::active_goals_ [protected] |
Definition at line 72 of file tf_web_republisher.cpp.
TFTransformServer TFRepublisher::as_ [protected] |
Definition at line 61 of file tf_web_republisher.cpp.
unsigned int TFRepublisher::client_ID_count_ [protected] |
Definition at line 85 of file tf_web_republisher.cpp.
boost::mutex TFRepublisher::goals_mutex_ [protected] |
Definition at line 73 of file tf_web_republisher.cpp.
ros::NodeHandle TFRepublisher::nh_ [protected] |
Definition at line 59 of file tf_web_republisher.cpp.
tf2::Buffer TFRepublisher::tf_buffer_ [protected] |
Definition at line 77 of file tf_web_republisher.cpp.
boost::mutex TFRepublisher::tf_buffer_mutex_ [protected] |
Definition at line 83 of file tf_web_republisher.cpp.
tf2::TransformListener TFRepublisher::tf_listener_ [protected] |
Definition at line 78 of file tf_web_republisher.cpp.