5#include <boost/optional/optional_io.hpp>
7#include <microstrain_mips/SetGyroBiasModel.h>
8#include <microstrain_mips/SetSensorVehicleFrameTrans.h>
9#include <microstrain_mips/SetTareOrientation.h>
10#include <microstrain_mips/SetComplementaryFilter.h>
11#include <microstrain_mips/SetFilterHeading.h>
12#include <microstrain_mips/SetAccelBias.h>
13#include <microstrain_mips/SetAccelNoise.h>
14#include <microstrain_mips/SetEstimationControlFlags.h>
15#include <microstrain_mips/SetAccelBiasModel.h>
16#include <microstrain_mips/SetConingScullingComp.h>
17#include <microstrain_mips/SetSensorVehicleFrameOffset.h>
18#include <microstrain_mips/SetGyroNoise.h>
19#include <microstrain_mips/SetFilterEuler.h>
20#include <microstrain_mips/SetReferencePosition.h>
21#include <microstrain_mips/SetMagDipAdaptiveVals.h>
22#include <microstrain_mips/SetZeroAngleUpdateThreshold.h>
23#include <microstrain_mips/SetHardIronValues.h>
24#include <microstrain_mips/SetMagNoise.h>
25#include <microstrain_mips/SetMagAdaptiveVals.h>
26#include <microstrain_mips/SetSoftIronMatrix.h>
27#include <microstrain_mips/SetDynamicsMode.h>
28#include <microstrain_mips/SetAccelAdaptiveVals.h>
29#include <microstrain_mips/SetGyroBias.h>
31#include <std_msgs/Empty.h>
32#include <std_srvs/Empty.h>
33#include <std_srvs/Trigger.h>
35#include <sensor_msgs/Imu.h>
36#include <microstrain_mips/status_msg.h>
40using namespace microstrain_mips;
62 ROS_ERROR(
"service client with no service name set. Skipping.");
66 ROS_INFO_STREAM(
"[" << this->
getName() <<
"] Client Service: " << *nodeName_);
72 this->
deviceReportSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"device_report");
74 this->
setSoftIronMatrixSrv =
nh_.serviceClient<microstrain_mips::SetSoftIronMatrix>(namebase +
"set_soft_iron_matrix");
76 this->
setFilterEulerSrv =
nh_.serviceClient<microstrain_mips::SetFilterEuler>(namebase +
"set_filter_euler");
77 this->
setFilterHeadingSrv =
nh_.serviceClient<microstrain_mips::SetFilterHeading>(namebase +
"set_filter_heading");
78 this->
setAccelBiasModelSrv =
nh_.serviceClient<microstrain_mips::SetAccelBiasModel>(namebase +
"set_accel_bias_model");
79 this->
setAccelAdaptiveValsSrv =
nh_.serviceClient<microstrain_mips::SetAccelAdaptiveVals>(namebase +
"set_accel_adaptive_vals");
82 this->
setAccelBiasSrv =
nh_.serviceClient<microstrain_mips::SetAccelBiasModel>(namebase +
"set_accel_bias");
83 this->
setGyroBiasSrv =
nh_.serviceClient<microstrain_mips::SetGyroBias>(namebase +
"set_gyro_bias");
84 this->
setHardIronValuesSrv =
nh_.serviceClient<microstrain_mips::SetHardIronValues>(namebase +
"set_hard_iron_values");
86 this->
getAccelBiasSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"get_accel_bias");
87 this->
getGyroBiasSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"get_gyro_bias");
93 this->
setReferencePositionSrv =
nh_.serviceClient<microstrain_mips::SetReferencePosition>(namebase +
"set_reference_position");
101 this->
setDynamicsModeSrv =
nh_.serviceClient<microstrain_mips::SetDynamicsMode>(namebase +
"set_dynamics_mode");
108 this->
setTareOrientationSrv =
nh_.serviceClient<microstrain_mips::SetTareOrientation>(namebase +
"set_tare_orientation");
110 this->
setAccelNoiseSrv =
nh_.serviceClient<microstrain_mips::SetAccelNoise>(namebase +
"set_accel_noise");
111 this->
getAccelNoiseSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"get_accel_noise");
113 this->
setGyroNoiseSrv =
nh_.serviceClient<microstrain_mips::SetGyroNoise>(namebase +
"set_gyro_noise");
114 this->
getGyroNoiseSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"get_gyro_noise");
116 this->
setMagNoiseSrv =
nh_.serviceClient<microstrain_mips::SetMagNoise>(namebase +
"set_mag_noise");
117 this->
getMagNoiseSrv =
nh_.serviceClient<std_srvs::Trigger>(namebase +
"get_mag_noise");
119 this->
setGyroBiasModelSrv =
nh_.serviceClient<microstrain_mips::SetGyroBiasModel>(namebase +
"set_gyro_bias_model");
124 this->
setMagAdaptiveValsSrv =
nh_.serviceClient<microstrain_mips::SetMagAdaptiveVals>(namebase +
"set_mag_adaptive_vals");
127 this->
setMagDipAdaptiveValsSrv =
nh_.serviceClient<microstrain_mips::SetMagDipAdaptiveVals>(namebase +
"set_mag_dip_adaptive_vals");
137 template <
typename TOrthogonal,
typename TSourceObject>
140 this->imuSubscriber = this->createComponent<TSourceObject, TOrthogonal, smacc::components::CpTopicSubscriber<sensor_msgs::Imu>>(
"imu/data");
141 this->imuFilteredSubscriber = this->createComponent<TSourceObject, TOrthogonal, smacc::components::CpTopicSubscriber<sensor_msgs::Imu>>(
"filtered/imu/data");
142 this->statusSubscriber = this->createComponent<TSourceObject, TOrthogonal, smacc::components::CpTopicSubscriber<microstrain_mips::status_msg>>(
"imu/data");
147 std_srvs::Empty::Request req;
148 std_srvs::Empty::Response res;
155 std_srvs::Trigger::Request req;
156 std_srvs::Trigger::Response res;
164 std_srvs::Trigger::Request req;
165 std_srvs::Trigger::Response res;
171 bool setSoftIronMatrix(
const geometry_msgs::Vector3 &soft_iron_1,
const geometry_msgs::Vector3 &soft_iron_2,
const geometry_msgs::Vector3 &soft_iron_3)
173 SetSoftIronMatrix::Request req;
174 SetSoftIronMatrix::Response res;
175 req.soft_iron_1 = soft_iron_1;
176 req.soft_iron_2 = soft_iron_2;
177 req.soft_iron_3 = soft_iron_3;
183 bool setComplementaryFilter(int8_t north_comp_enable, int8_t up_comp_enable,
float north_comp_time_const,
float up_comp_time_const)
185 SetComplementaryFilter::Request req;
186 SetComplementaryFilter::Response res;
188 req.north_comp_enable = north_comp_enable;
189 req.up_comp_enable = up_comp_enable;
190 req.north_comp_time_const = north_comp_time_const;
191 req.up_comp_time_const = up_comp_time_const;
199 SetFilterEuler::Request req;
200 SetFilterEuler::Response res;
209 SetFilterHeading::Request req;
210 SetFilterHeading::Response res;
217 bool setAccelBiasModel(
const geometry_msgs::Vector3 &noise_vector,
const geometry_msgs::Vector3 &beta_vector)
219 SetAccelBiasModel::Request req;
220 SetAccelBiasModel::Response res;
221 req.noise_vector = noise_vector;
222 req.beta_vector = beta_vector;
228 bool setAccelAdaptiveVals(
float enable,
float low_pass_cutoff,
float min_1sigma,
float low_limit,
float high_limit,
float low_limit_1sigma,
float high_limit_1sigma)
230 SetAccelAdaptiveVals::Request req;
231 SetAccelAdaptiveVals::Response res;
234 req.low_pass_cutoff = low_pass_cutoff;
235 req.min_1sigma = min_1sigma;
236 req.low_limit = low_limit;
237 req.high_limit = high_limit;
238 req.low_limit_1sigma = low_limit_1sigma;
239 req.high_limit_1sigma = high_limit_1sigma;
247 SetSensorVehicleFrameTrans::Request req;
248 SetSensorVehicleFrameTrans::Response res;
257 SetSensorVehicleFrameOffset::Request req;
258 SetSensorVehicleFrameOffset::Response res;
267 SetAccelBias::Request req;
268 SetAccelBias::Response res;
277 SetGyroBias::Request req;
278 SetGyroBias::Response res;
287 SetHardIronValues::Request req;
288 SetHardIronValues::Response res;
297 std_srvs::Trigger::Request req;
298 std_srvs::Trigger::Response res;
306 std_srvs::Trigger::Request req;
307 std_srvs::Trigger::Response res;
315 std_srvs::Trigger::Request req;
316 std_srvs::Trigger::Response res;
324 std_srvs::Trigger::Request req;
325 std_srvs::Trigger::Response res;
333 std_srvs::Trigger::Request req;
334 std_srvs::Trigger::Response res;
342 std_srvs::Trigger::Request req;
343 std_srvs::Trigger::Response res;
351 SetReferencePosition::Request req;
352 SetReferencePosition::Response res;
353 req.position = position;
361 std_srvs::Trigger::Request req;
362 std_srvs::Trigger::Response res;
370 SetConingScullingComp::Request req;
371 SetConingScullingComp::Response res;
380 std_srvs::Trigger::Request req;
381 std_srvs::Trigger::Response res;
389 SetEstimationControlFlags::Request req;
390 SetEstimationControlFlags::Response res;
399 std_srvs::Trigger::Request req;
400 std_srvs::Trigger::Response res;
408 SetDynamicsMode::Request req;
409 SetDynamicsMode::Response res;
418 std_srvs::Trigger::Request req;
419 std_srvs::Trigger::Response res;
427 std_srvs::Trigger::Request req;
428 std_srvs::Trigger::Response res;
436 SetZeroAngleUpdateThreshold::Request req;
437 SetZeroAngleUpdateThreshold::Response res;
439 req.threshold = threshold;
447 std_srvs::Trigger::Request req;
448 std_srvs::Trigger::Response res;
456 SetTareOrientation::Request req;
457 SetTareOrientation::Response res;
466 SetAccelNoise::Request req;
467 SetAccelNoise::Response res;
476 std_srvs::Trigger::Request req;
477 std_srvs::Trigger::Response res;
485 SetGyroNoise::Request req;
486 SetGyroNoise::Response res;
495 std_srvs::Trigger::Request req;
496 std_srvs::Trigger::Response res;
504 SetMagNoise::Request req;
505 SetMagNoise::Response res;
515 std_srvs::Trigger::Request req;
516 std_srvs::Trigger::Response res;
522 bool setGyroBiasModel(
const geometry_msgs::Vector3 &noise_vector,
const geometry_msgs::Vector3 &beta_vector)
524 SetGyroBiasModel::Request req;
525 SetGyroBiasModel::Response res;
526 req.noise_vector = noise_vector;
527 req.beta_vector = beta_vector;
535 std_srvs::Trigger::Request req;
536 std_srvs::Trigger::Response res;
544 std_srvs::Trigger::Request req;
545 std_srvs::Trigger::Response res;
551 bool setMagAdaptiveVals(
float enable,
float low_pass_cutoff,
float min_1sigma,
float low_limit,
float high_limit,
float low_limit_1sigma,
float high_limit_1sigma)
553 SetMagAdaptiveVals::Request req;
554 SetMagAdaptiveVals::Response res;
557 req.low_pass_cutoff = low_pass_cutoff;
558 req.min_1sigma = min_1sigma;
559 req.low_limit = low_limit;
560 req.high_limit = high_limit;
561 req.low_limit_1sigma = low_limit_1sigma;
562 req.high_limit_1sigma = high_limit_1sigma;
570 std_srvs::Trigger::Request req;
571 std_srvs::Trigger::Response res;
577 bool setMagDipAdaptiveVals(
float enable,
float low_pass_cutoff,
float min_1sigma,
float high_limit,
float high_limit_1sigma)
579 SetMagDipAdaptiveVals::Request req;
580 SetMagDipAdaptiveVals::Response res;
583 req.low_pass_cutoff = low_pass_cutoff;
584 req.min_1sigma = min_1sigma;
585 req.high_limit = high_limit;
586 req.high_limit_1sigma = high_limit_1sigma;
594 std_srvs::Trigger::Request req;
595 std_srvs::Trigger::Response res;
603 std_srvs::Trigger::Request req;
604 std_srvs::Trigger::Response res;
612 std_srvs::Trigger::Request req;
613 std_srvs::Trigger::Response res;
621 std_srvs::Trigger::Request req;
622 std_srvs::Trigger::Response res;
ros::ServiceClient setMagNoiseSrv
smacc::components::CpTopicSubscriber< microstrain_mips::status_msg > * statusSubscriber
ros::ServiceClient setAccelAdaptiveValsSrv
ros::ServiceClient getHardIronValuesSrv
ros::ServiceClient getSensorVehicleFrameOffsetSrv
bool getSensorVehicleFrameTrans()
bool setMagDipAdaptiveVals(float enable, float low_pass_cutoff, float min_1sigma, float high_limit, float high_limit_1sigma)
bool getReferencePosition()
ros::ServiceClient getReferencePositionSrv
bool setSoftIronMatrix(const geometry_msgs::Vector3 &soft_iron_1, const geometry_msgs::Vector3 &soft_iron_2, const geometry_msgs::Vector3 &soft_iron_3)
bool setGyroNoise(const geometry_msgs::Vector3 &noise)
ros::ServiceClient setGyroBiasSrv
bool setSensorVehicleFrameOffset(const geometry_msgs::Vector3 &offset)
bool setReferencePosition(const geometry_msgs::Vector3 &position)
ros::ServiceClient setSoftIronMatrixSrv
ros::ServiceClient setEstimationControlFlagsSrv
ros::ServiceClient getGyroBiasSrv
ros::ServiceClient setMagDipAdaptiveValsSrv
ros::ServiceClient getComplementaryFilterSrv
ros::ServiceClient getDiagnosticReportSrv
ros::ServiceClient resetFilterSrv
ros::ServiceClient setDynamicsModeSrv
bool setAccelAdaptiveVals(float enable, float low_pass_cutoff, float min_1sigma, float low_limit, float high_limit, float low_limit_1sigma, float high_limit_1sigma)
boost::optional< std::string > nodeName_
void onOrthogonalAllocation()
ros::ServiceClient getGyroBiasModelSrv
bool setSensorVehicleFrameTrans(const geometry_msgs::Vector3 &angle)
bool setComplementaryFilter(int8_t north_comp_enable, int8_t up_comp_enable, float north_comp_time_const, float up_comp_time_const)
ros::ServiceClient setFilterEulerSrv
bool setAccelBias(const geometry_msgs::Vector3 &bias)
ros::ServiceClient setComplementaryFilterSrv
ros::ServiceClient getAccelBiasModelSrv
ros::ServiceClient gyroBiasCaptureSrv
ros::ServiceClient getGynamicsModeSrv
ros::ServiceClient getEstimationControlFlagsSrv
bool getConingScullingComp()
bool setMagNoise(const geometry_msgs::Vector3 &noise)
bool setHardIronValues(const geometry_msgs::Vector3 &bias)
bool getMagAdaptiveVals()
ros::ServiceClient setGyroNoiseSrv
smacc::components::CpTopicSubscriber< sensor_msgs::Imu > * imuSubscriber
ros::ServiceClient getSoftIronMatrixSrv
bool setZeroAngleUpdateThreshold(int8_t enable, float threshold)
ros::ServiceClient setReferencePositionSrv
ros::ServiceClient getGyroNoiseSrv
ros::ServiceClient getAccelBiasSrv
ros::ServiceClient getMagAdaptiveValsSrv
bool setAccelBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
ros::ServiceClient getAccelAdaptiveValsSrv
bool setTareOrientation(int8_t axis)
ros::ServiceClient getMagNoiseSrv
ros::ServiceClient getConingScullingCompSrv
ros::ServiceClient setZeroAngleUpdateThresholdSrv
bool setEstimationControlFlags(int8_t flag)
ros::ServiceClient setAccelBiasModelSrv
ros::ServiceClient deviceReportSrv
ros::ServiceClient setGyroBiasModelSrv
ros::ServiceClient setSensorVehicleFrameOffsetSrv
bool setConingScullingComp(int8_t enable)
ros::ServiceClient getMagDipAdaptiveValsSrv
bool setDynamicsMode(int8_t mode)
bool setGyroBias(const geometry_msgs::Vector3 &bias)
bool getAccelAdaptiveVals()
bool getComplementaryFilter()
ros::ServiceClient getBasicStatusSrv
virtual void initialize() override
ros::ServiceClient setHardIronValuesSrv
ros::ServiceClient setFilterHeadingSrv
ros::ServiceClient getSensorVehicleFrameTransSrv
ros::ServiceClient setSensorVehicleFrameTransSrv
bool setGyroBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
bool getSensorVehicleFrameOffset()
bool getEstimationControlFlags()
bool setMagAdaptiveVals(float enable, float low_pass_cutoff, float min_1sigma, float low_limit, float high_limit, float low_limit_1sigma, float high_limit_1sigma)
bool getDiagnosticReport()
bool setFilterHeading(float angle)
ros::ServiceClient setConingScullingCompSrv
ros::ServiceClient setAccelBiasSrv
ros::ServiceClient getAccelNoiseSrv
bool getMagDipAdaptiveVals()
smacc::components::CpTopicSubscriber< sensor_msgs::Imu > * imuFilteredSubscriber
ros::ServiceClient getZeroAngleUpdateThresholdSrv
ros::ServiceClient setMagAdaptiveValsSrv
ros::ServiceClient setAccelNoiseSrv
bool setAccelNoise(const geometry_msgs::Vector3 &noise)
bool setFilterEulerService(const geometry_msgs::Vector3 &angle)
bool getZeroAngleUpdateThreshold()
ros::ServiceClient setTareOrientationSrv
virtual std::string getName() const