SMACC
Loading...
Searching...
No Matches
microstrain_mips_client.h
Go to the documentation of this file.
1
2#pragma once
3#include <smacc/smacc.h>
5#include <boost/optional/optional_io.hpp>
6
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>
30
31#include <std_msgs/Empty.h>
32#include <std_srvs/Empty.h>
33#include <std_srvs/Trigger.h>
34
35#include <sensor_msgs/Imu.h>
36#include <microstrain_mips/status_msg.h>
37
39{
40using namespace microstrain_mips;
41
43{
44public:
45 boost::optional<std::string> nodeName_;
46
50
52 {
53 initialized_ = false;
54 }
55
56 virtual void initialize() override
57 {
58 if (!initialized_)
59 {
60 if (!nodeName_)
61 {
62 ROS_ERROR("service client with no service name set. Skipping.");
63 }
64 else
65 {
66 ROS_INFO_STREAM("[" << this->getName() << "] Client Service: " << *nodeName_);
67 this->initialized_ = true;
68
69 std::string namebase = *nodeName_ + "/";
70
71 this->resetFilterSrv = nh_.serviceClient<std_srvs::Empty>(namebase + "reset_kf");
72 this->deviceReportSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "device_report");
73 this->gyroBiasCaptureSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "gyro_bias_capture");
74 this->setSoftIronMatrixSrv = nh_.serviceClient<microstrain_mips::SetSoftIronMatrix>(namebase + "set_soft_iron_matrix");
75 this->setComplementaryFilterSrv = nh_.serviceClient<microstrain_mips::SetComplementaryFilter>(namebase + "set_complementary_filter");
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");
80 this->setSensorVehicleFrameTransSrv = nh_.serviceClient<microstrain_mips::SetSensorVehicleFrameTrans>(namebase + "set_sensor_vehicle_frame_trans");
81 this->setSensorVehicleFrameOffsetSrv = nh_.serviceClient<microstrain_mips::SetSensorVehicleFrameOffset>(namebase + "set_sensor_vehicle_frame_offset");
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");
85
86 this->getAccelBiasSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_accel_bias");
87 this->getGyroBiasSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_gyro_bias");
88 this->getHardIronValuesSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_hard_iron_values");
89 this->getSoftIronMatrixSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_soft_iron_matrix");
90 this->getSensorVehicleFrameTransSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_sensor_vehicle_frame_trans");
91 this->getComplementaryFilterSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_complementary_filter");
92
93 this->setReferencePositionSrv = nh_.serviceClient<microstrain_mips::SetReferencePosition>(namebase + "set_reference_position");
94 this->getReferencePositionSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_reference_position");
95 this->setConingScullingCompSrv = nh_.serviceClient<microstrain_mips::SetConingScullingComp>(namebase + "set_coning_sculling_comp");
96 this->getConingScullingCompSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_coning_sculling_comp");
97
98 this->setEstimationControlFlagsSrv = nh_.serviceClient<microstrain_mips::SetEstimationControlFlags>(namebase + "set_estimation_control_flags");
99 this->getEstimationControlFlagsSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_estimation_control_flags");
100
101 this->setDynamicsModeSrv = nh_.serviceClient<microstrain_mips::SetDynamicsMode>(namebase + "set_dynamics_mode");
102 this->getBasicStatusSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_basic_status");
103 this->getDiagnosticReportSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_diagnostic_report");
104
105 this->setZeroAngleUpdateThresholdSrv = nh_.serviceClient<microstrain_mips::SetZeroAngleUpdateThreshold>(namebase + "set_zero_angle_update_threshold"); // -
106 this->getZeroAngleUpdateThresholdSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_zero_angle_update_threshold"); // -
107
108 this->setTareOrientationSrv = nh_.serviceClient<microstrain_mips::SetTareOrientation>(namebase + "set_tare_orientation");
109
110 this->setAccelNoiseSrv = nh_.serviceClient<microstrain_mips::SetAccelNoise>(namebase + "set_accel_noise");
111 this->getAccelNoiseSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_accel_noise");
112
113 this->setGyroNoiseSrv = nh_.serviceClient<microstrain_mips::SetGyroNoise>(namebase + "set_gyro_noise");
114 this->getGyroNoiseSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_gyro_noise");
115
116 this->setMagNoiseSrv = nh_.serviceClient<microstrain_mips::SetMagNoise>(namebase + "set_mag_noise");
117 this->getMagNoiseSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_mag_noise");
118
119 this->setGyroBiasModelSrv = nh_.serviceClient<microstrain_mips::SetGyroBiasModel>(namebase + "set_gyro_bias_model");
120 this->getGyroBiasModelSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_gyro_bias_model");
121
122 this->getAccelAdaptiveValsSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_accel_adaptive_vals");
123
124 this->setMagAdaptiveValsSrv = nh_.serviceClient<microstrain_mips::SetMagAdaptiveVals>(namebase + "set_mag_adaptive_vals");
125 this->getMagAdaptiveValsSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_mag_adaptive_vals");
126
127 this->setMagDipAdaptiveValsSrv = nh_.serviceClient<microstrain_mips::SetMagDipAdaptiveVals>(namebase + "set_mag_dip_adaptive_vals");
128 this->getAccelBiasModelSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_accel_bias_model");
129
130 this->getMagDipAdaptiveValsSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_mag_dip_adaptive_vals");
131 this->getSensorVehicleFrameOffsetSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_sensor_vehicle_frame_offset");
132 this->getGynamicsModeSrv = nh_.serviceClient<std_srvs::Trigger>(namebase + "get_dynamics_mode");
133 }
134 }
135 }
136
137 template <typename TOrthogonal, typename TSourceObject>
139 {
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");
143 }
144
146 {
147 std_srvs::Empty::Request req;
148 std_srvs::Empty::Response res;
149
150 resetFilterSrv.call(req, res);
151 }
152
154 {
155 std_srvs::Trigger::Request req;
156 std_srvs::Trigger::Response res;
157
158 deviceReportSrv.call(req, res);
159 return res.success;
160 }
161
163 {
164 std_srvs::Trigger::Request req;
165 std_srvs::Trigger::Response res;
166
167 gyroBiasCaptureSrv.call(req, res);
168 return res.success;
169 }
170
171 bool setSoftIronMatrix(const geometry_msgs::Vector3 &soft_iron_1, const geometry_msgs::Vector3 &soft_iron_2, const geometry_msgs::Vector3 &soft_iron_3)
172 {
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;
178
179 setSoftIronMatrixSrv.call(req, res);
180 return res.success;
181 }
182
183 bool setComplementaryFilter(int8_t north_comp_enable, int8_t up_comp_enable, float north_comp_time_const, float up_comp_time_const)
184 {
185 SetComplementaryFilter::Request req;
186 SetComplementaryFilter::Response res;
187
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;
192
193 setComplementaryFilterSrv.call(req, res);
194 return res.success;
195 }
196
197 bool setFilterEulerService(const geometry_msgs::Vector3 &angle)
198 {
199 SetFilterEuler::Request req;
200 SetFilterEuler::Response res;
201 req.angle = angle;
202
203 setFilterEulerSrv.call(req, res);
204 return res.success;
205 }
206
207 bool setFilterHeading(float angle)
208 {
209 SetFilterHeading::Request req;
210 SetFilterHeading::Response res;
211 req.angle = angle;
212
213 setFilterHeadingSrv.call(req, res);
214 return res.success;
215 }
216
217 bool setAccelBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
218 {
219 SetAccelBiasModel::Request req;
220 SetAccelBiasModel::Response res;
221 req.noise_vector = noise_vector;
222 req.beta_vector = beta_vector;
223
224 setAccelBiasModelSrv.call(req, res);
225 return res.success;
226 }
227
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)
229 {
230 SetAccelAdaptiveVals::Request req;
231 SetAccelAdaptiveVals::Response res;
232
233 req.enable = enable;
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;
240
241 setAccelAdaptiveValsSrv.call(req, res);
242 return res.success;
243 }
244
245 bool setSensorVehicleFrameTrans(const geometry_msgs::Vector3 &angle)
246 {
247 SetSensorVehicleFrameTrans::Request req;
248 SetSensorVehicleFrameTrans::Response res;
249 req.angle = angle;
250
251 setSensorVehicleFrameTransSrv.call(req, res);
252 return res.success;
253 }
254
255 bool setSensorVehicleFrameOffset(const geometry_msgs::Vector3 &offset)
256 {
257 SetSensorVehicleFrameOffset::Request req;
258 SetSensorVehicleFrameOffset::Response res;
259 req.offset = offset;
260
261 setSensorVehicleFrameOffsetSrv.call(req, res);
262 return res.success;
263 }
264
265 bool setAccelBias(const geometry_msgs::Vector3 &bias)
266 {
267 SetAccelBias::Request req;
268 SetAccelBias::Response res;
269 req.bias = bias;
270
271 setAccelBiasSrv.call(req, res);
272 return res.success;
273 }
274
275 bool setGyroBias(const geometry_msgs::Vector3 &bias)
276 {
277 SetGyroBias::Request req;
278 SetGyroBias::Response res;
279 req.bias = bias;
280
281 setGyroBiasSrv.call(req, res);
282 return res.success;
283 }
284
285 bool setHardIronValues(const geometry_msgs::Vector3 &bias)
286 {
287 SetHardIronValues::Request req;
288 SetHardIronValues::Response res;
289 req.bias = bias;
290
291 setHardIronValuesSrv.call(req, res);
292 return res.success;
293 }
294
296 {
297 std_srvs::Trigger::Request req;
298 std_srvs::Trigger::Response res;
299
300 getAccelBiasSrv.call(req, res);
301 return res.success;
302 }
303
305 {
306 std_srvs::Trigger::Request req;
307 std_srvs::Trigger::Response res;
308
309 getGyroBiasSrv.call(req, res);
310 return res.success;
311 }
312
314 {
315 std_srvs::Trigger::Request req;
316 std_srvs::Trigger::Response res;
317
318 getHardIronValuesSrv.call(req, res);
319 return res.success;
320 }
321
323 {
324 std_srvs::Trigger::Request req;
325 std_srvs::Trigger::Response res;
326
327 getSoftIronMatrixSrv.call(req, res);
328 return res.success;
329 }
330
332 {
333 std_srvs::Trigger::Request req;
334 std_srvs::Trigger::Response res;
335
336 getSensorVehicleFrameTransSrv.call(req, res);
337 return res.success;
338 }
339
341 {
342 std_srvs::Trigger::Request req;
343 std_srvs::Trigger::Response res;
344
345 getComplementaryFilterSrv.call(req, res);
346 return res.success;
347 }
348
349 bool setReferencePosition(const geometry_msgs::Vector3 &position)
350 {
351 SetReferencePosition::Request req;
352 SetReferencePosition::Response res;
353 req.position = position;
354
355 setReferencePositionSrv.call(req, res);
356 return res.success;
357 }
358
360 {
361 std_srvs::Trigger::Request req;
362 std_srvs::Trigger::Response res;
363
364 getReferencePositionSrv.call(req, res);
365 return res.success;
366 }
367
368 bool setConingScullingComp(int8_t enable)
369 {
370 SetConingScullingComp::Request req;
371 SetConingScullingComp::Response res;
372 req.enable = enable;
373
374 setConingScullingCompSrv.call(req, res);
375 return res.success;
376 }
377
379 {
380 std_srvs::Trigger::Request req;
381 std_srvs::Trigger::Response res;
382
383 getConingScullingCompSrv.call(req, res);
384 return res.success;
385 }
386
388 {
389 SetEstimationControlFlags::Request req;
390 SetEstimationControlFlags::Response res;
391 req.flag = flag;
392
393 setEstimationControlFlagsSrv.call(req, res);
394 return res.success;
395 }
396
398 {
399 std_srvs::Trigger::Request req;
400 std_srvs::Trigger::Response res;
401
402 getEstimationControlFlagsSrv.call(req, res);
403 return res.success;
404 }
405
406 bool setDynamicsMode(int8_t mode)
407 {
408 SetDynamicsMode::Request req;
409 SetDynamicsMode::Response res;
410 req.mode = mode;
411
412 setDynamicsModeSrv.call(req, res);
413 return res.success;
414 }
415
417 {
418 std_srvs::Trigger::Request req;
419 std_srvs::Trigger::Response res;
420
421 getBasicStatusSrv.call(req, res);
422 return res.success;
423 }
424
426 {
427 std_srvs::Trigger::Request req;
428 std_srvs::Trigger::Response res;
429
430 getDiagnosticReportSrv.call(req, res);
431 return res.success;
432 }
433
434 bool setZeroAngleUpdateThreshold(int8_t enable, float threshold)
435 {
436 SetZeroAngleUpdateThreshold::Request req;
437 SetZeroAngleUpdateThreshold::Response res;
438 req.enable = enable;
439 req.threshold = threshold;
440
441 setZeroAngleUpdateThresholdSrv.call(req, res);
442 return res.success;
443 }
444
446 {
447 std_srvs::Trigger::Request req;
448 std_srvs::Trigger::Response res;
449
450 getZeroAngleUpdateThresholdSrv.call(req, res);
451 return res.success;
452 }
453
454 bool setTareOrientation(int8_t axis)
455 {
456 SetTareOrientation::Request req;
457 SetTareOrientation::Response res;
458 req.axis = axis;
459
460 setTareOrientationSrv.call(req, res);
461 return res.success;
462 }
463
464 bool setAccelNoise(const geometry_msgs::Vector3 &noise)
465 {
466 SetAccelNoise::Request req;
467 SetAccelNoise::Response res;
468 req.noise = noise;
469
470 setAccelNoiseSrv.call(req, res);
471 return res.success;
472 }
473
475 {
476 std_srvs::Trigger::Request req;
477 std_srvs::Trigger::Response res;
478
479 getAccelNoiseSrv.call(req, res);
480 return res.success;
481 }
482
483 bool setGyroNoise(const geometry_msgs::Vector3 &noise)
484 {
485 SetGyroNoise::Request req;
486 SetGyroNoise::Response res;
487 req.noise = noise;
488
489 setGyroNoiseSrv.call(req, res);
490 return res.success;
491 }
492
494 {
495 std_srvs::Trigger::Request req;
496 std_srvs::Trigger::Response res;
497
498 getGyroNoiseSrv.call(req, res);
499 return res.success;
500 }
501
502 bool setMagNoise(const geometry_msgs::Vector3 &noise)
503 {
504 SetMagNoise::Request req;
505 SetMagNoise::Response res;
506
507 req.noise = noise;
508
509 setMagNoiseSrv.call(req, res);
510 return res.success;
511 }
512
514 {
515 std_srvs::Trigger::Request req;
516 std_srvs::Trigger::Response res;
517
518 getMagNoiseSrv.call(req, res);
519 return res.success;
520 }
521
522 bool setGyroBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
523 {
524 SetGyroBiasModel::Request req;
525 SetGyroBiasModel::Response res;
526 req.noise_vector = noise_vector;
527 req.beta_vector = beta_vector;
528
529 setGyroBiasModelSrv.call(req, res);
530 return res.success;
531 }
532
534 {
535 std_srvs::Trigger::Request req;
536 std_srvs::Trigger::Response res;
537
538 getGyroBiasModelSrv.call(req, res);
539 return res.success;
540 }
541
543 {
544 std_srvs::Trigger::Request req;
545 std_srvs::Trigger::Response res;
546
547 getAccelAdaptiveValsSrv.call(req, res);
548 return res.success;
549 }
550
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)
552 {
553 SetMagAdaptiveVals::Request req;
554 SetMagAdaptiveVals::Response res;
555
556 req.enable = enable;
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;
563
564 setMagAdaptiveValsSrv.call(req, res);
565 return res.success;
566 }
567
569 {
570 std_srvs::Trigger::Request req;
571 std_srvs::Trigger::Response res;
572
573 getMagAdaptiveValsSrv.call(req, res);
574 return res.success;
575 }
576
577 bool setMagDipAdaptiveVals(float enable, float low_pass_cutoff, float min_1sigma, float high_limit, float high_limit_1sigma)
578 {
579 SetMagDipAdaptiveVals::Request req;
580 SetMagDipAdaptiveVals::Response res;
581
582 req.enable = enable;
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;
587
588 setMagDipAdaptiveValsSrv.call(req, res);
589 return res.success;
590 }
591
593 {
594 std_srvs::Trigger::Request req;
595 std_srvs::Trigger::Response res;
596
597 getAccelBiasModelSrv.call(req, res);
598 return res.success;
599 }
600
602 {
603 std_srvs::Trigger::Request req;
604 std_srvs::Trigger::Response res;
605
606 getMagDipAdaptiveValsSrv.call(req, res);
607 return res.success;
608 }
609
611 {
612 std_srvs::Trigger::Request req;
613 std_srvs::Trigger::Response res;
614
615 getSensorVehicleFrameOffsetSrv.call(req, res);
616 return res.success;
617 }
618
620 {
621 std_srvs::Trigger::Request req;
622 std_srvs::Trigger::Response res;
623
624 getGynamicsModeSrv.call(req, res);
625 return res.success;
626 }
627
628protected:
629 ros::NodeHandle nh_;
631
632 ros::ServiceClient resetFilterSrv; // reset_kf - std_srvs::Empty
633 ros::ServiceClient deviceReportSrv; // device_report - std_srvs::Trigger
634 ros::ServiceClient gyroBiasCaptureSrv; // gyro_bias_capture - std_srvs::Trigger
635 ros::ServiceClient setSoftIronMatrixSrv; // set_soft_iron_matrix - microstrain_mips::SetSoftIronMatrix
636 ros::ServiceClient setComplementaryFilterSrv; //set_complementary_filter - microstrain_mips::SetComplementaryFilter
637 ros::ServiceClient setFilterEulerSrv; // set_filter_euler - microstrain_mips::SetFilterEuler
638 ros::ServiceClient setFilterHeadingSrv; // set_filter_heading - microstrain_mips::SetFilterHeading
639 ros::ServiceClient setAccelBiasModelSrv; // set_accel_bias_model - microstrain_mips::SetAccelBiasModel
640 ros::ServiceClient setAccelAdaptiveValsSrv; // set_accel_adaptive_vals - microstrain_mips::SetAccelAdaptiveVals
641 ros::ServiceClient setSensorVehicleFrameTransSrv; // set_sensor_vehicle_frame_trans - microstrain_mips::SetSensorVehicleFrameTrans
642 ros::ServiceClient setSensorVehicleFrameOffsetSrv; // set_sensor_vehicle_frame_offset - microstrain_mips::SetSensorVehicleFrameOffset
643 ros::ServiceClient setAccelBiasSrv; // set_accel_bias - microstrain_mips::SetAccelBiasModel
644 ros::ServiceClient setGyroBiasSrv; // set_gyro_bias - microstrain_mips::SetGyroBias
645 ros::ServiceClient setHardIronValuesSrv; // set_hard_iron_values - microstrain_mips::SetHardIronValues
646 ros::ServiceClient getAccelBiasSrv; // get_accel_bias - std_srvs::Trigger
647 ros::ServiceClient getGyroBiasSrv; // get_gyro_bias - std_srvs::Trigger
648 ros::ServiceClient getHardIronValuesSrv; // get_hard_iron_values - std_srvs::Trigger
649 ros::ServiceClient getSoftIronMatrixSrv; // get_soft_iron_matrix - std_srvs::Trigger
650 ros::ServiceClient getSensorVehicleFrameTransSrv; // get_sensor_vehicle_frame_trans - std_srvs::Trigger
651 ros::ServiceClient getComplementaryFilterSrv; // get_complementary_filter - std_srvs::Trigger
652 ros::ServiceClient setReferencePositionSrv; // set_reference_position - microstrain_mips::SetReferencePosition
653 ros::ServiceClient getReferencePositionSrv; // get_reference_position - std_srvs::Trigger
654 ros::ServiceClient setConingScullingCompSrv; // set_coning_sculling_comp - microstrain_mips::SetConingScullingComp
655 ros::ServiceClient getConingScullingCompSrv; // get_coning_sculling_comp - std_srvs::Trigger
656 ros::ServiceClient setEstimationControlFlagsSrv; // set_estimation_control_flags - microstrain_mips::SetEstimationControlFlags
657 ros::ServiceClient getEstimationControlFlagsSrv; // get_estimation_control_flags - std_srvs::Trigger
658 ros::ServiceClient setDynamicsModeSrv; // set_dynamics_mode - microstrain_mips::SetDynamicsMode
659 ros::ServiceClient getBasicStatusSrv; // get_basic_status - std_srvs::Trigger
660 ros::ServiceClient getDiagnosticReportSrv; // get_diagnostic_report - std_srvs::Trigger
661 ros::ServiceClient setZeroAngleUpdateThresholdSrv; // set_zero_angle_update_threshold - microstrain_mips::SetZeroAngleUpdateThreshold
662 ros::ServiceClient getZeroAngleUpdateThresholdSrv; // get_zero_angle_update_threshold - std_srvs::Trigger
663 ros::ServiceClient setTareOrientationSrv; // set_tare_orientation - microstrain_mips::SetTareOrientation
664 ros::ServiceClient setAccelNoiseSrv; // set_accel_noise - microstrain_mips::SetAccelNoise
665 ros::ServiceClient getAccelNoiseSrv; // get_accel_noise - std_srvs::Trigger
666 ros::ServiceClient setGyroNoiseSrv; // set_gyro_noise - microstrain_mips::SetGyroNoise
667 ros::ServiceClient getGyroNoiseSrv; // get_gyro_noise - std_srvs::Trigger
668 ros::ServiceClient setMagNoiseSrv; // set_mag_noise - microstrain_mips::SetMagNoise
669 ros::ServiceClient getMagNoiseSrv; // get_mag_noise - std_srvs::Trigger
670 ros::ServiceClient setGyroBiasModelSrv; // set_gyro_bias_model - microstrain_mips::SetGyroBiasModel
671 ros::ServiceClient getGyroBiasModelSrv; // get_gyro_bias_model - std_srvs::Trigger
672 ros::ServiceClient getAccelAdaptiveValsSrv; // get_accel_adaptive_vals - std_srvs::Trigger
673 ros::ServiceClient setMagAdaptiveValsSrv; // set_mag_adaptive_vals - microstrain_mips::SetMagAdaptiveVals
674 ros::ServiceClient getMagAdaptiveValsSrv; // get_mag_adaptive_vals - std_srvs::Trigger
675 ros::ServiceClient setMagDipAdaptiveValsSrv; // set_mag_dip_adaptive_vals - microstrain_mips::SetMagDipAdaptiveVals
676 ros::ServiceClient getAccelBiasModelSrv; // get_accel_bias_model - std_srvs::Trigger
677 ros::ServiceClient getMagDipAdaptiveValsSrv; // get_mag_dip_adaptive_vals - std_srvs::Trigger
678 ros::ServiceClient getSensorVehicleFrameOffsetSrv; // get_sensor_vehicle_frame_offset - std_srvs::Trigger
679 ros::ServiceClient getGynamicsModeSrv; // get_dynamics_mode - std_srvs::Trigger
680};
681}
smacc::components::CpTopicSubscriber< microstrain_mips::status_msg > * statusSubscriber
bool setMagDipAdaptiveVals(float enable, float low_pass_cutoff, float min_1sigma, float high_limit, float high_limit_1sigma)
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)
bool setSensorVehicleFrameOffset(const geometry_msgs::Vector3 &offset)
bool setReferencePosition(const geometry_msgs::Vector3 &position)
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_
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)
bool setAccelBias(const geometry_msgs::Vector3 &bias)
bool setMagNoise(const geometry_msgs::Vector3 &noise)
bool setHardIronValues(const geometry_msgs::Vector3 &bias)
smacc::components::CpTopicSubscriber< sensor_msgs::Imu > * imuSubscriber
bool setZeroAngleUpdateThreshold(int8_t enable, float threshold)
bool setAccelBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
bool setGyroBias(const geometry_msgs::Vector3 &bias)
bool setGyroBiasModel(const geometry_msgs::Vector3 &noise_vector, const geometry_msgs::Vector3 &beta_vector)
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)
smacc::components::CpTopicSubscriber< sensor_msgs::Imu > * imuFilteredSubscriber
bool setAccelNoise(const geometry_msgs::Vector3 &noise)
bool setFilterEulerService(const geometry_msgs::Vector3 &angle)
virtual std::string getName() const
Definition: client.cpp:34