Configuration.h
Go to the documentation of this file.
1 #ifndef CONFIGURATION_H
2 #define CONFIGURATION_H
3 
5 #include <muse_v2_driver/GetConfigurationParams.h>
6 #include <muse_v2_driver/SetConfigurationParams.h>
7 
8 namespace muse_v2_driver {
9 
11  {
12  public:
13 
14  struct CommandList
15  {
20  bool get_log_mode = false;
21  bool get_log_frequency = false;
22 
23  uint16_t gyroscope_full_scale = 0;
27  uint8_t log_mode = UINT8_MAX;
28  uint8_t log_frequency = UINT8_MAX;
29 
30  bool operator==(const CommandList& rhs) const {
31  return (
36  (get_log_mode == rhs.get_log_mode) &&
41  (log_mode == rhs.log_mode)&&
43  );
44  }
45 
47 
49 
50  Configuration() = default;
51  ~Configuration() = default;
52 
54  bool getConfigurationParams(GetConfigurationParams::Request& req, GetConfigurationParams::Response& res, MuseV2* muse_v2);
55  bool setConfigurationParams(SetConfigurationParams::Request& req, SetConfigurationParams::Response& res, MuseV2* muse_v2);
56 
57  };
58 }
59 
60 #endif
muse_v2_driver::Configuration::getConfigurationParams
bool getConfigurationParams(GetConfigurationParams::Request &req, GetConfigurationParams::Response &res, MuseV2 *muse_v2)
Definition: Configuration.cpp:27
muse_v2_driver::Configuration::CommandList::get_log_mode
bool get_log_mode
Definition: Configuration.h:20
muse_v2_driver
Definition: Calibration.h:9
muse_v2_driver::Configuration::CommandList::gyroscope_full_scale
uint16_t gyroscope_full_scale
Definition: Configuration.h:23
muse_v2_driver::Configuration::CommandList::log_mode
uint8_t log_mode
Definition: Configuration.h:27
muse_v2_driver::Configuration::CommandList::log_frequency
uint8_t log_frequency
Definition: Configuration.h:28
muse_v2_driver::Configuration::default_command_list
struct muse_v2_driver::Configuration::CommandList default_command_list
muse_v2_driver::Configuration::CommandList::operator==
bool operator==(const CommandList &rhs) const
Definition: Configuration.h:30
muse_v2_driver::Configuration::CommandList::accelerometer_full_scale
uint8_t accelerometer_full_scale
Definition: Configuration.h:24
muse_v2_driver::Configuration::input_command
CommandList input_command
Definition: Configuration.h:48
MuseV2.h
muse_v2_driver::Configuration::CommandList::get_accelerometer_full_scale
bool get_accelerometer_full_scale
Definition: Configuration.h:17
muse_v2_driver::Configuration::CommandList::magnetometer_full_scale
uint8_t magnetometer_full_scale
Definition: Configuration.h:26
muse_v2_driver::Configuration::Configuration
Configuration()=default
muse_v2_driver::Configuration::CommandList::get_log_frequency
bool get_log_frequency
Definition: Configuration.h:21
muse_v2_driver::Configuration::received_command
CommandList received_command
Definition: Configuration.h:48
muse_v2_driver::Configuration::~Configuration
~Configuration()=default
muse_v2_driver::Configuration::setupInputCommands
void setupInputCommands(ros::NodeHandle &node)
Definition: Configuration.cpp:3
muse_v2_driver::MuseV2
Definition: MuseV2.h:21
muse_v2_driver::Configuration::CommandList::get_accelerometer_hdr_full_scale
bool get_accelerometer_hdr_full_scale
Definition: Configuration.h:18
muse_v2_driver::Configuration::CommandList::get_gyroscope_full_scale
bool get_gyroscope_full_scale
Definition: Configuration.h:16
muse_v2_driver::Configuration::CommandList
Definition: Configuration.h:14
muse_v2_driver::Configuration
Definition: Configuration.h:10
muse_v2_driver::Configuration::CommandList::accelerometer_hdr_full_scale
uint16_t accelerometer_hdr_full_scale
Definition: Configuration.h:25
muse_v2_driver::Configuration::CommandList::get_magnetometer_full_scale
bool get_magnetometer_full_scale
Definition: Configuration.h:19
ros::NodeHandle
muse_v2_driver::Configuration::setConfigurationParams
bool setConfigurationParams(SetConfigurationParams::Request &req, SetConfigurationParams::Response &res, MuseV2 *muse_v2)
Definition: Configuration.cpp:109


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