Stream.h
Go to the documentation of this file.
1 #ifndef STREAM_H
2 #define STREAM_H
3 
5 
6 #include <geometry_msgs/QuaternionStamped.h>
7 #include <geometry_msgs/Vector3Stamped.h>
8 #include <sensor_msgs/Imu.h>
9 #include <sensor_msgs/MagneticField.h>
10 #include <muse_v2_driver/Transmission.h>
11 
12 #include <muse_v2/MuseV2_HW.h>
13 
14 #include <tf/tf.h>
15 
16 namespace muse_v2_driver {
17 
18  class Stream
19  {
20  public:
21 
22  struct CommandList
23  {
24  bool get_imu = false;
25  bool get_quaternion = false;
26  bool get_angular_velocity = false;
27  bool get_acceleration = false;
28  bool get_mag = false;
29  bool get_rpy = false;
30 
31  bool operator==(const CommandList& rhs) const {
32  return (
33  (get_imu == rhs.get_imu) &&
34  (get_quaternion == rhs.get_quaternion) &&
38  (get_mag == rhs.get_mag) &&
39  (get_rpy == rhs.get_rpy)
40  );
41  }
42 
44 
45  enum CommandType {
52  };
53 
55 
56  geometry_msgs::QuaternionStamped quaternion_msg;
57  geometry_msgs::Vector3Stamped rpy_msg;
58  geometry_msgs::Vector3Stamped angular_velocity_msg;
59  geometry_msgs::Vector3Stamped acceleration_msg;
60  sensor_msgs::MagneticField mag_msg;
61  sensor_msgs::Imu imu_msg;
62 
64 
65  Stream() = default;
66  Stream(ros::NodeHandle& node, int pub_queue_size = 10);
67  ~Stream() = default;
68 
70  bool isFrequencyAdmissible(int frequency);
71  void StreamRawData(const Transmission::ConstPtr& msg, MuseV2* muse_v2);
72 
73  };
74 }
75 
76 #endif
muse_v2_driver
Definition: Calibration.h:9
muse_v2_driver::Stream::GET_MAG
@ GET_MAG
Definition: Stream.h:50
muse_v2_driver::Stream::mag_msg
sensor_msgs::MagneticField mag_msg
Definition: Stream.h:60
ros::Publisher
muse_v2_driver::Stream::CommandList
Definition: Stream.h:22
muse_v2_driver::Stream::imu_msg
sensor_msgs::Imu imu_msg
Definition: Stream.h:61
muse_v2_driver::Stream::acceleration_msg
geometry_msgs::Vector3Stamped acceleration_msg
Definition: Stream.h:59
muse_v2_driver::Stream::rpy_msg
geometry_msgs::Vector3Stamped rpy_msg
Definition: Stream.h:57
muse_v2_driver::Stream::angular_velocity_msg
geometry_msgs::Vector3Stamped angular_velocity_msg
Definition: Stream.h:58
muse_v2_driver::Stream::pub_angular_velocity
ros::Publisher pub_angular_velocity
Definition: Stream.h:63
muse_v2_driver::Stream::StreamRawData
void StreamRawData(const Transmission::ConstPtr &msg, MuseV2 *muse_v2)
Definition: Stream.cpp:35
muse_v2_driver::Stream::received_command
CommandList received_command
Definition: Stream.h:54
muse_v2_driver::Stream::pub_acceleration
ros::Publisher pub_acceleration
Definition: Stream.h:63
muse_v2_driver::Stream::GET_ACCELERATION
@ GET_ACCELERATION
Definition: Stream.h:49
muse_v2_driver::Stream::CommandList::get_mag
bool get_mag
Definition: Stream.h:28
muse_v2_driver::Stream::CommandList::get_acceleration
bool get_acceleration
Definition: Stream.h:27
muse_v2_driver::Stream::GET_QUATERNION
@ GET_QUATERNION
Definition: Stream.h:47
MuseV2.h
muse_v2_driver::Stream::GET_ANGULAR_VELOCITY
@ GET_ANGULAR_VELOCITY
Definition: Stream.h:48
muse_v2_driver::Stream::CommandList::operator==
bool operator==(const CommandList &rhs) const
Definition: Stream.h:31
muse_v2_driver::Stream::default_command_list
struct muse_v2_driver::Stream::CommandList default_command_list
muse_v2_driver::Stream::~Stream
~Stream()=default
muse_v2_driver::Stream::pub_mag
ros::Publisher pub_mag
Definition: Stream.h:63
muse_v2_driver::Stream::setupInputCommands
void setupInputCommands(ros::NodeHandle &node)
Definition: Stream.cpp:14
muse_v2_driver::Stream::input_command
CommandList input_command
Definition: Stream.h:54
muse_v2_driver::Stream
Definition: Stream.h:18
muse_v2_driver::Stream::CommandList::get_quaternion
bool get_quaternion
Definition: Stream.h:25
muse_v2_driver::Stream::CommandList::get_imu
bool get_imu
Definition: Stream.h:24
tf.h
muse_v2_driver::Stream::CommandList::get_angular_velocity
bool get_angular_velocity
Definition: Stream.h:26
muse_v2_driver::Stream::GET_RPY
@ GET_RPY
Definition: Stream.h:51
muse_v2_driver::Stream::CommandList::get_rpy
bool get_rpy
Definition: Stream.h:29
muse_v2_driver::Stream::GET_IMU
@ GET_IMU
Definition: Stream.h:46
muse_v2_driver::MuseV2
Definition: MuseV2.h:21
muse_v2_driver::Stream::pub_imu
ros::Publisher pub_imu
Definition: Stream.h:63
muse_v2_driver::Stream::pub_rpy
ros::Publisher pub_rpy
Definition: Stream.h:63
muse_v2_driver::Stream::pub_quaternion
ros::Publisher pub_quaternion
Definition: Stream.h:63
muse_v2_driver::Stream::isFrequencyAdmissible
bool isFrequencyAdmissible(int frequency)
Definition: Stream.cpp:24
muse_v2_driver::Stream::quaternion_msg
geometry_msgs::QuaternionStamped quaternion_msg
Definition: Stream.h:56
muse_v2_driver::Stream::CommandType
CommandType
Definition: Stream.h:45
ros::NodeHandle
muse_v2_driver::Stream::Stream
Stream()=default


muse_v2_driver
Author(s): Elisa Tosello , Roberto Bortoletto
autogenerated on Thu Jan 20 2022 03:24:53