get_configuration_params.cpp
Go to the documentation of this file.
2 
3 int main(int argc, char** argv)
4 {
5  ros::init(argc, argv, "get_configuration_params");
6 
8 
10 
11  config.setupInputCommands(n);
12 
13  ros::ServiceClient client = n.serviceClient<muse_v2_driver::GetConfigurationParams>("get_configuration_params");
14 
15  if (config.input_command == config.default_command_list) {
16  ROS_ERROR("No request found.");
17  ros::shutdown();
18  return -1;
19  }
20 
21  muse_v2_driver::GetConfigurationParams srv;
22 
24  srv.request.get_gyroscope_full_scale = true;
25 
27  srv.request.get_accelerometer_full_scale = true;
28 
30  srv.request.get_accelerometer_hdr_full_scale = true;
31 
33  srv.request.get_magnetometer_full_scale = true;
34 
35  if (config.input_command.get_log_mode)
36  srv.request.get_log_mode = true;
37 
39  srv.request.get_log_frequency = true;
40 
41  if (client.call(srv))
42  {
43  if (srv.request.get_gyroscope_full_scale)
44  ROS_INFO("Gyroscope Full-Scale [dps]: %u", srv.response.gyroscope_full_scale);
45 
46  if (srv.request.get_accelerometer_full_scale)
47  ROS_INFO("Accelerometer Full-Scale [g]: %u", srv.response.accelerometer_full_scale);
48 
49  if (srv.request.get_accelerometer_hdr_full_scale)
50  ROS_INFO("Accelerometer HDR Full-Scale [g]: %u", srv.response.accelerometer_hdr_full_scale);
51 
52  if (srv.request.get_magnetometer_full_scale)
53  ROS_INFO("Magnetometer Full-Scale [G]: %u", srv.response.magnetometer_full_scale);
54 
55  if (srv.request.get_log_mode)
56  ROS_INFO("Log Mode: %u", srv.response.log_mode);
57 
58  if (srv.request.get_log_frequency)
59  ROS_INFO("Log Frequency: %u", srv.response.log_frequency);
60  }
61  else
62  {
63  ROS_ERROR("Failed to call Get Configuration Params service.");
64  return 1;
65  }
66 
67  return 0;
68 }
muse_v2_driver::Configuration::CommandList::get_log_mode
bool get_log_mode
Definition: Configuration.h:20
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
muse_v2_driver::Configuration::default_command_list
struct muse_v2_driver::Configuration::CommandList default_command_list
ros::shutdown
ROSCPP_DECL void shutdown()
main
int main(int argc, char **argv)
Definition: get_configuration_params.cpp:3
muse_v2_driver::Configuration::input_command
CommandList input_command
Definition: Configuration.h:48
muse_v2_driver::Configuration::CommandList::get_accelerometer_full_scale
bool get_accelerometer_full_scale
Definition: Configuration.h:17
ros::ServiceClient
muse_v2_driver::Configuration::CommandList::get_log_frequency
bool get_log_frequency
Definition: Configuration.h:21
muse_v2_driver::Configuration::setupInputCommands
void setupInputCommands(ros::NodeHandle &node)
Definition: Configuration.cpp:3
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
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
ROS_INFO
#define ROS_INFO(...)
muse_v2_driver::Configuration
Definition: Configuration.h:10
Configuration.h
muse_v2_driver::Configuration::CommandList::get_magnetometer_full_scale
bool get_magnetometer_full_scale
Definition: Configuration.h:19
ros::NodeHandle


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