hebiros_subscribers_physical.h
Go to the documentation of this file.
1 #ifndef HEBIROS_SUBSCRIBERS_PHYSICAL_H
2 #define HEBIROS_SUBSCRIBERS_PHYSICAL_H
3 
4 #include "ros/ros.h"
5 #include "sensor_msgs/JointState.h"
6 #include "hebiros/CommandMsg.h"
7 
8 #include "hebiros_subscribers.h"
9 #include "group_feedback.hpp"
10 #include "group_command.hpp"
11 
12 
14 
15  public:
16 
17  void registerGroupSubscribers(std::string group_name);
19  std::string group_name);
21  std::string group_name);
22  void feedback(std::string group_name, const hebi::GroupFeedback& group_fbk);
23  static void addJointCommand(hebi::GroupCommand* group_command,
24  sensor_msgs::JointState data, std::string group_name);
25  static void addSettingsCommand(hebi::GroupCommand* group_command,
26  hebiros::SettingsMsg data, std::string group_name);
27  static void addPositionGainsCommand(hebi::GroupCommand* group_command,
28  hebiros::PidGainsMsg data, std::string group_name);
29  static void addVelocityGainsCommand(hebi::GroupCommand* group_command,
30  hebiros::PidGainsMsg data, std::string group_name);
31  static void addEffortGainsCommand(hebi::GroupCommand* group_command,
32  hebiros::PidGainsMsg data, std::string group_name);
33 
34 };
35 
36 #endif
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)


hebiros
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:08:14