#include <hebiros_publishers_gazebo.h>

Public Member Functions | |
| void | command (hebiros::CommandMsg command_msg, std::string group_name) |
| void | registerGroupPublishers (std::string group_name) |
Public Member Functions inherited from HebirosPublishers | |
| void | commandJointState (sensor_msgs::JointState joint_state_msg, std::string group_name) |
| void | feedback (hebiros::FeedbackMsg feedback_msg, std::string group_name) |
| void | feedbackJointState (sensor_msgs::JointState joint_state_msg, std::string group_name) |
| void | feedbackJointStateUrdf (sensor_msgs::JointState joint_state_msg, std::string group_name) |
| void | registerGroupPublishers (std::string group_name) |
Additional Inherited Members | |
Static Public Attributes inherited from HebirosPublishers | |
| static std::map< std::string, ros::Publisher > | publishers |
Definition at line 9 of file hebiros_publishers_gazebo.h.
| void HebirosPublishersGazebo::command | ( | hebiros::CommandMsg | command_msg, |
| std::string | group_name | ||
| ) |
Definition at line 17 of file hebiros_publishers_gazebo.cpp.
| void HebirosPublishersGazebo::registerGroupPublishers | ( | std::string | group_name | ) |
Definition at line 8 of file hebiros_publishers_gazebo.cpp.