#include <hebiros_publishers.h>
Public Member Functions | |
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) |
Static Public Attributes | |
static std::map< std::string, ros::Publisher > | publishers |
Definition at line 10 of file hebiros_publishers.h.
void HebirosPublishers::commandJointState | ( | sensor_msgs::JointState | joint_state_msg, |
std::string | group_name | ||
) |
Definition at line 55 of file hebiros_publishers.cpp.
void HebirosPublishers::feedback | ( | hebiros::FeedbackMsg | feedback_msg, |
std::string | group_name | ||
) |
Definition at line 30 of file hebiros_publishers.cpp.
void HebirosPublishers::feedbackJointState | ( | sensor_msgs::JointState | joint_state_msg, |
std::string | group_name | ||
) |
Definition at line 34 of file hebiros_publishers.cpp.
void HebirosPublishers::feedbackJointStateUrdf | ( | sensor_msgs::JointState | joint_state_msg, |
std::string | group_name | ||
) |
Definition at line 41 of file hebiros_publishers.cpp.
void HebirosPublishers::registerGroupPublishers | ( | std::string | group_name | ) |
Definition at line 11 of file hebiros_publishers.cpp.
|
static |
Definition at line 14 of file hebiros_publishers.h.