hebiros_group.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "ros/ros.h"
4 #include "sensor_msgs/JointState.h"
5 
6 #include "hebiros/FeedbackMsg.h"
7 
8 // Base class for physical and simulated groups of modules.
9 class HebirosGroup {
10 
11  public:
12 
13  HebirosGroup();
14  virtual ~HebirosGroup() = default;
15 
16  int size;
17  std::map<std::string, std::string> joint_full_names;
18  std::map<std::string, int> joints;
19  sensor_msgs::JointState joint_state_msg;
20  hebiros::FeedbackMsg feedback_msg;
21 
22  virtual void setFeedbackFrequency(float frequency_hz);
23  virtual void setCommandLifetime(float lifetime_ms);
24 };
virtual void setFeedbackFrequency(float frequency_hz)
sensor_msgs::JointState joint_state_msg
Definition: hebiros_group.h:19
virtual ~HebirosGroup()=default
hebiros::FeedbackMsg feedback_msg
Definition: hebiros_group.h:20
virtual void setCommandLifetime(float lifetime_ms)
std::map< std::string, int > joints
Definition: hebiros_group.h:18
std::map< std::string, std::string > joint_full_names
Definition: hebiros_group.h:17


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