Public Member Functions | |
| void | callback (const ros::MessageEvent< tf::tfMessage const > &msg_evt) |
| std::string | outputFrameInfo (const std::map< std::string, std::vector< double > >::iterator &it, const std::string &frame_authority) |
| void | process_callback (const tf::tfMessage &message, const std::string &authority, bool is_static) |
| void | spin () |
| void | static_callback (const ros::MessageEvent< tf::tfMessage const > &msg_evt) |
| TFMonitor (bool using_specific_chain, std::string framea="", std::string frameb="") | |
Public Attributes | |
| std::map< std::string, std::vector< double > > | authority_frequency_map |
| std::map< std::string, std::vector< double > > | authority_map |
| std::vector< std::string > | chain_ |
| std::map< std::string, std::vector< double > > | delay_map |
| std::map< std::string, std::string > | frame_authority_map |
| std::string | framea_ |
| std::string | frameb_ |
| boost::mutex | map_lock_ |
| tf::tfMessage | message_ |
| ros::NodeHandle | node_ |
| ros::Subscriber | subscriber_tf_ |
| ros::Subscriber | subscriber_tf_static_ |
| TransformListener | tf_ |
| bool | using_specific_chain_ |
Definition at line 47 of file tf_monitor.cpp.
|
inline |
Definition at line 144 of file tf_monitor.cpp.
|
inline |
Definition at line 66 of file tf_monitor.cpp.
|
inline |
Definition at line 176 of file tf_monitor.cpp.
|
inline |
Definition at line 81 of file tf_monitor.cpp.
|
inline |
Definition at line 191 of file tf_monitor.cpp.
|
inline |
Definition at line 73 of file tf_monitor.cpp.
| std::map<std::string, std::vector<double> > TFMonitor::authority_frequency_map |
Definition at line 59 of file tf_monitor.cpp.
| std::map<std::string, std::vector<double> > TFMonitor::authority_map |
Definition at line 58 of file tf_monitor.cpp.
| std::vector<std::string> TFMonitor::chain_ |
Definition at line 55 of file tf_monitor.cpp.
| std::map<std::string, std::vector<double> > TFMonitor::delay_map |
Definition at line 57 of file tf_monitor.cpp.
| std::map<std::string, std::string> TFMonitor::frame_authority_map |
Definition at line 56 of file tf_monitor.cpp.
| std::string TFMonitor::framea_ |
Definition at line 50 of file tf_monitor.cpp.
| std::string TFMonitor::frameb_ |
Definition at line 50 of file tf_monitor.cpp.
| boost::mutex TFMonitor::map_lock_ |
Definition at line 65 of file tf_monitor.cpp.
| tf::tfMessage TFMonitor::message_ |
Definition at line 63 of file tf_monitor.cpp.
| ros::NodeHandle TFMonitor::node_ |
Definition at line 53 of file tf_monitor.cpp.
| ros::Subscriber TFMonitor::subscriber_tf_ |
Definition at line 54 of file tf_monitor.cpp.
| ros::Subscriber TFMonitor::subscriber_tf_static_ |
Definition at line 54 of file tf_monitor.cpp.
| TransformListener TFMonitor::tf_ |
Definition at line 61 of file tf_monitor.cpp.
| bool TFMonitor::using_specific_chain_ |
Definition at line 51 of file tf_monitor.cpp.