3 int main(
int argc,
char** argv)
5 ros::init(argc, argv,
"get_configuration_params");
21 muse_v2_driver::GetConfigurationParams srv;
24 srv.request.get_gyroscope_full_scale =
true;
27 srv.request.get_accelerometer_full_scale =
true;
30 srv.request.get_accelerometer_hdr_full_scale =
true;
33 srv.request.get_magnetometer_full_scale =
true;
36 srv.request.get_log_mode =
true;
39 srv.request.get_log_frequency =
true;
43 if (srv.request.get_gyroscope_full_scale)
44 ROS_INFO(
"Gyroscope Full-Scale [dps]: %u", srv.response.gyroscope_full_scale);
46 if (srv.request.get_accelerometer_full_scale)
47 ROS_INFO(
"Accelerometer Full-Scale [g]: %u", srv.response.accelerometer_full_scale);
49 if (srv.request.get_accelerometer_hdr_full_scale)
50 ROS_INFO(
"Accelerometer HDR Full-Scale [g]: %u", srv.response.accelerometer_hdr_full_scale);
52 if (srv.request.get_magnetometer_full_scale)
53 ROS_INFO(
"Magnetometer Full-Scale [G]: %u", srv.response.magnetometer_full_scale);
55 if (srv.request.get_log_mode)
56 ROS_INFO(
"Log Mode: %u", srv.response.log_mode);
58 if (srv.request.get_log_frequency)
59 ROS_INFO(
"Log Frequency: %u", srv.response.log_frequency);
63 ROS_ERROR(
"Failed to call Get Configuration Params service.");