Publishes RVIZ transforms used to visualize a robot's URDF. More...
#include <urdf_visualizer.h>
| Public Member Functions | |
| UrdfVisualizer (const std::string &urdf_name, const std::vector< URDFName > &joint_names_in_urdf, const URDFName &base_link_in_urdf, const std::string &rviz_fixed_frame, const std::string &state_topic, const std::string &tf_prefix="") | |
| Constructs the visualizer for a specific URDF urdf_name. | |
| virtual | ~UrdfVisualizer () | 
| Private Member Functions | |
| UrdfnameToJointAngle | AssignAngleToURDFJointName (const sensor_msgs::JointState &msg) const | 
| geometry_msgs::TransformStamped | GetBaseFromRos (const ::ros::Time &stamp, const geometry_msgs::Pose &msg) const | 
| void | StateCallback (const xpp_msgs::RobotStateJoint &msg) | 
| Private Attributes | |
| URDFName | base_joint_in_urdf_ | 
| std::vector< URDFName > | joint_names_in_urdf_ | 
| std::shared_ptr < robot_state_publisher::RobotStatePublisher > | robot_publisher | 
| std::string | rviz_fixed_frame_ | 
| std::string | state_msg_name_ | 
| ros::Subscriber | state_sub_des_ | 
| tf::TransformBroadcaster | tf_broadcaster_ | 
| std::string | tf_prefix_ | 
Publishes RVIZ transforms used to visualize a robot's URDF.
This class is responsible for converting an xpp_msgs::RobotStateJoint robot message and publishing the corresponding RVIZ transforms.
Definition at line 60 of file urdf_visualizer.h.
| xpp::UrdfVisualizer::UrdfVisualizer | ( | const std::string & | urdf_name, | 
| const std::vector< URDFName > & | joint_names_in_urdf, | ||
| const URDFName & | base_link_in_urdf, | ||
| const std::string & | rviz_fixed_frame, | ||
| const std::string & | state_topic, | ||
| const std::string & | tf_prefix = "" | ||
| ) | 
Constructs the visualizer for a specific URDF urdf_name.
| urdf_name | Robot description variable on the ROS parameter server. | 
| joint_names_in_urdf | The names of the joints in the URDF file ordered in the same way as in the xpp convention (see inverse kinematics). | 
| base_link_in_urdf | The name of the base_link in the URDF file. | 
| rviz_fixed_frame | The Fixed Frame name specified in RVIZ. | 
| state_topic | The topic of the xpp_msgs::RobotStateJoint ROS message to subscribe to. | 
| tf_prefix | In case multiple URDFS are loaded, each can be given a unique tf_prefix in RIVZ to visualize different states simultaneously. | 
Definition at line 34 of file urdf_visualizer.cc.
| virtual xpp::UrdfVisualizer::~UrdfVisualizer | ( | ) |  [virtual] | 
| UrdfVisualizer::UrdfnameToJointAngle xpp::UrdfVisualizer::AssignAngleToURDFJointName | ( | const sensor_msgs::JointState & | msg | ) | const  [private] | 
Definition at line 78 of file urdf_visualizer.cc.
| geometry_msgs::TransformStamped xpp::UrdfVisualizer::GetBaseFromRos | ( | const ::ros::Time & | stamp, | 
| const geometry_msgs::Pose & | msg | ||
| ) | const  [private] | 
Definition at line 89 of file urdf_visualizer.cc.
| void xpp::UrdfVisualizer::StateCallback | ( | const xpp_msgs::RobotStateJoint & | msg | ) |  [private] | 
Definition at line 67 of file urdf_visualizer.cc.
| URDFName xpp::UrdfVisualizer::base_joint_in_urdf_  [private] | 
Definition at line 98 of file urdf_visualizer.h.
| std::vector<URDFName> xpp::UrdfVisualizer::joint_names_in_urdf_  [private] | 
Definition at line 97 of file urdf_visualizer.h.
| std::shared_ptr<robot_state_publisher::RobotStatePublisher> xpp::UrdfVisualizer::robot_publisher  [private] | 
Definition at line 89 of file urdf_visualizer.h.
| std::string xpp::UrdfVisualizer::rviz_fixed_frame_  [private] | 
Definition at line 101 of file urdf_visualizer.h.
| std::string xpp::UrdfVisualizer::state_msg_name_  [private] | 
Definition at line 100 of file urdf_visualizer.h.
Definition at line 87 of file urdf_visualizer.h.
Definition at line 88 of file urdf_visualizer.h.
| std::string xpp::UrdfVisualizer::tf_prefix_  [private] | 
Definition at line 102 of file urdf_visualizer.h.