Classes | |
struct | ClientGoalInfo |
struct | ClientInfo |
struct | ClientRequestInfo |
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 &) |
void | processRequest (boost::shared_ptr< ClientRequestInfo > request_info, const ros::TimerEvent &) |
bool | requestCB (Request &req, Response &res) |
void | setSubscriptions (boost::shared_ptr< ClientInfo > info, const std::vector< std::string > &source_frames, const std::string &target_frame_, float angular_thres, float trans_thres) const |
TFRepublisher (const std::string &name) | |
void | unadvertiseCB (boost::shared_ptr< ClientRequestInfo > request_info, const ros::TimerEvent &) |
void | updateSubscriptions (std::vector< TFPair > &tf_subscriptions, std::vector< geometry_msgs::TransformStamped > &transforms) |
~TFRepublisher () | |
Protected Types | |
typedef TFTransformServer::GoalHandle | GoalHandle |
typedef tf2_web_republisher::RepublishTFs::Request | Request |
typedef tf2_web_republisher::RepublishTFs::Response | Response |
typedef actionlib::ActionServer< tf2_web_republisher::TFSubscriptionAction > | TFTransformServer |
Protected Attributes | |
std::list< boost::shared_ptr< ClientGoalInfo > > | active_goals_ |
std::list< boost::shared_ptr< ClientRequestInfo > > | active_requests_ |
TFTransformServer | as_ |
unsigned int | client_ID_count_ |
boost::mutex | goals_mutex_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | priv_nh_ |
boost::mutex | requests_mutex_ |
tf2::Buffer | tf_buffer_ |
boost::mutex | tf_buffer_mutex_ |
tf2::TransformListener | tf_listener_ |
ros::ServiceServer | tf_republish_service_ |
Definition at line 57 of file tf_web_republisher.cpp.
|
protected |
Definition at line 61 of file tf_web_republisher.cpp.
|
protected |
Definition at line 63 of file tf_web_republisher.cpp.
|
protected |
Definition at line 64 of file tf_web_republisher.cpp.
|
protected |
Definition at line 60 of file tf_web_republisher.cpp.
|
inline |
Definition at line 115 of file tf_web_republisher.cpp.
|
inline |
Definition at line 133 of file tf_web_republisher.cpp.
|
inline |
Definition at line 137 of file tf_web_republisher.cpp.
|
inline |
Definition at line 159 of file tf_web_republisher.cpp.
|
inline |
Definition at line 195 of file tf_web_republisher.cpp.
|
inline |
Definition at line 351 of file tf_web_republisher.cpp.
|
inline |
Definition at line 369 of file tf_web_republisher.cpp.
Definition at line 228 of file tf_web_republisher.cpp.
|
inline |
Set up the contents of tf_subscriptions_
in a ClientInfo struct
Definition at line 172 of file tf_web_republisher.cpp.
|
inline |
Definition at line 266 of file tf_web_republisher.cpp.
|
inline |
Definition at line 289 of file tf_web_republisher.cpp.
|
protected |
Definition at line 95 of file tf_web_republisher.cpp.
|
protected |
Definition at line 98 of file tf_web_republisher.cpp.
|
protected |
Definition at line 69 of file tf_web_republisher.cpp.
|
protected |
Definition at line 111 of file tf_web_republisher.cpp.
|
protected |
Definition at line 96 of file tf_web_republisher.cpp.
|
protected |
Definition at line 66 of file tf_web_republisher.cpp.
|
protected |
Definition at line 67 of file tf_web_republisher.cpp.
|
protected |
Definition at line 99 of file tf_web_republisher.cpp.
|
protected |
Definition at line 103 of file tf_web_republisher.cpp.
|
protected |
Definition at line 109 of file tf_web_republisher.cpp.
|
protected |
Definition at line 104 of file tf_web_republisher.cpp.
|
protected |
Definition at line 70 of file tf_web_republisher.cpp.