1 #ifndef HEBIROS_SUBSCRIBERS_PHYSICAL_H 2 #define HEBIROS_SUBSCRIBERS_PHYSICAL_H 5 #include "sensor_msgs/JointState.h" 6 #include "hebiros/CommandMsg.h" 19 std::string group_name);
21 std::string group_name);
24 sensor_msgs::JointState data, std::string group_name);
26 hebiros::SettingsMsg data, std::string group_name);
28 hebiros::PidGainsMsg data, std::string group_name);
30 hebiros::PidGainsMsg data, std::string group_name);
32 hebiros::PidGainsMsg data, std::string group_name);
static void addEffortGainsCommand(hebi::GroupCommand *group_command, hebiros::PidGainsMsg data, std::string group_name)
A list of Feedback objects that can be received from a Group of modules; the size() must match the nu...
void command(const boost::shared_ptr< hebiros::CommandMsg const > data, std::string group_name)
void registerGroupSubscribers(std::string group_name)
static void addVelocityGainsCommand(hebi::GroupCommand *group_command, hebiros::PidGainsMsg data, std::string group_name)
static void addSettingsCommand(hebi::GroupCommand *group_command, hebiros::SettingsMsg data, std::string group_name)
static void addJointCommand(hebi::GroupCommand *group_command, sensor_msgs::JointState data, std::string group_name)
static void addPositionGainsCommand(hebi::GroupCommand *group_command, hebiros::PidGainsMsg data, std::string group_name)
A list of Command objects appropriate for sending to a Group of modules; the size() must match the nu...
void jointCommand(const boost::shared_ptr< sensor_msgs::JointState const > data, std::string group_name)
void feedback(std::string group_name, const hebi::GroupFeedback &group_fbk)