Go to the documentation of this file. 1 #ifndef CONFIGURATION_H
2 #define CONFIGURATION_H
5 #include <muse_v2_driver/GetConfigurationParams.h>
6 #include <muse_v2_driver/SetConfigurationParams.h>
bool getConfigurationParams(GetConfigurationParams::Request &req, GetConfigurationParams::Response &res, MuseV2 *muse_v2)
uint16_t gyroscope_full_scale
struct muse_v2_driver::Configuration::CommandList default_command_list
bool operator==(const CommandList &rhs) const
uint8_t accelerometer_full_scale
CommandList input_command
bool get_accelerometer_full_scale
uint8_t magnetometer_full_scale
CommandList received_command
void setupInputCommands(ros::NodeHandle &node)
bool get_accelerometer_hdr_full_scale
bool get_gyroscope_full_scale
uint16_t accelerometer_hdr_full_scale
bool get_magnetometer_full_scale
bool setConfigurationParams(SetConfigurationParams::Request &req, SetConfigurationParams::Response &res, MuseV2 *muse_v2)
muse_v2_driver
Author(s): Elisa Tosello
, Roberto Bortoletto
autogenerated on Thu Jan 20 2022 03:24:53