-
Notifications
You must be signed in to change notification settings - Fork 369
/
node.cpp
1604 lines (1435 loc) · 62 KB
/
node.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
//==============================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND
// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//==============================================================================
#include "ublox_gps/node.h"
using namespace ublox_node;
//
// ublox_node namespace
//
uint8_t ublox_node::modelFromString(const std::string& model) {
std::string lower = model;
std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
if(lower == "portable") {
return ublox_msgs::CfgNAV5::DYN_MODEL_PORTABLE;
} else if(lower == "stationary") {
return ublox_msgs::CfgNAV5::DYN_MODEL_STATIONARY;
} else if(lower == "pedestrian") {
return ublox_msgs::CfgNAV5::DYN_MODEL_PEDESTRIAN;
} else if(lower == "automotive") {
return ublox_msgs::CfgNAV5::DYN_MODEL_AUTOMOTIVE;
} else if(lower == "sea") {
return ublox_msgs::CfgNAV5::DYN_MODEL_SEA;
} else if(lower == "airborne1") {
return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_1G;
} else if(lower == "airborne2") {
return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_2G;
} else if(lower == "airborne4") {
return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_4G;
} else if(lower == "wristwatch") {
return ublox_msgs::CfgNAV5::DYN_MODEL_WRIST_WATCH;
}
throw std::runtime_error("Invalid settings: " + lower +
" is not a valid dynamic model.");
}
uint8_t ublox_node::fixModeFromString(const std::string& mode) {
std::string lower = mode;
std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
if (lower == "2d") {
return ublox_msgs::CfgNAV5::FIX_MODE_2D_ONLY;
} else if (lower == "3d") {
return ublox_msgs::CfgNAV5::FIX_MODE_3D_ONLY;
} else if (lower == "auto") {
return ublox_msgs::CfgNAV5::FIX_MODE_AUTO;
}
throw std::runtime_error("Invalid settings: " + mode +
" is not a valid fix mode.");
}
//
// u-blox ROS Node
//
UbloxNode::UbloxNode() {
initialize();
}
void UbloxNode::addFirmwareInterface() {
int ublox_version;
if (protocol_version_ < 14) {
components_.push_back(ComponentPtr(new UbloxFirmware6));
ublox_version = 6;
} else if (protocol_version_ >= 14 && protocol_version_ <= 15) {
components_.push_back(ComponentPtr(new UbloxFirmware7));
ublox_version = 7;
} else {
components_.push_back(ComponentPtr(new UbloxFirmware8));
ublox_version = 8;
}
ROS_INFO("U-Blox Firmware Version: %d", ublox_version);
}
void UbloxNode::addProductInterface(std::string product_category,
std::string ref_rov) {
if (product_category.compare("HPG") == 0 && ref_rov.compare("REF") == 0)
components_.push_back(ComponentPtr(new HpgRefProduct));
else if (product_category.compare("HPG") == 0 && ref_rov.compare("ROV") == 0)
components_.push_back(ComponentPtr(new HpgRovProduct));
else if (product_category.compare("TIM") == 0)
components_.push_back(ComponentPtr(new TimProduct));
else if (product_category.compare("ADR") == 0 ||
product_category.compare("UDR") == 0)
components_.push_back(ComponentPtr(new AdrUdrProduct));
else if (product_category.compare("FTS") == 0)
components_.push_back(ComponentPtr(new FtsProduct));
else if(product_category.compare("SPG") != 0)
ROS_WARN("Product category %s %s from MonVER message not recognized %s",
product_category.c_str(), ref_rov.c_str(),
"options are HPG REF, HPG ROV, TIM, ADR, UDR, FTS, SPG");
}
void UbloxNode::getRosParams() {
nh->param("device", device_, std::string("/dev/ttyACM0"));
nh->param("frame_id", frame_id, std::string("gps"));
// Save configuration parameters
getRosUint("load/mask", load_.loadMask, 0);
getRosUint("load/device", load_.deviceMask, 0);
getRosUint("save/mask", save_.saveMask, 0);
getRosUint("save/device", save_.deviceMask, 0);
// UART 1 params
getRosUint("uart1/baudrate", baudrate_, 9600);
getRosUint("uart1/in", uart_in_, ublox_msgs::CfgPRT::PROTO_UBX
| ublox_msgs::CfgPRT::PROTO_NMEA
| ublox_msgs::CfgPRT::PROTO_RTCM);
getRosUint("uart1/out", uart_out_, ublox_msgs::CfgPRT::PROTO_UBX);
// USB params
if (nh->hasParam("usb/in") || nh->hasParam("usb/out")) {
set_usb_ = true;
if(!getRosUint("usb/in", usb_in_)) {
throw std::runtime_error(std::string("usb/out is set, therefore ") +
"usb/in must be set");
}
if(!getRosUint("usb/out", usb_out_)) {
throw std::runtime_error(std::string("usb/in is set, therefore ") +
"usb/out must be set");
}
getRosUint("usb/tx_ready", usb_tx_, 0);
}
// Measurement rate params
nh->param("rate", rate_, 4.0); // in Hz
getRosUint("nav_rate", nav_rate, 1); // # of measurement rate cycles
// RTCM params
getRosUint("rtcm/ids", rtcm_ids); // RTCM output message IDs
getRosUint("rtcm/rates", rtcm_rates); // RTCM output message rates
// PPP: Advanced Setting
nh->param("enable_ppp", enable_ppp_, false);
// SBAS params, only for some devices
nh->param("sbas", enable_sbas_, false);
getRosUint("sbas/max", max_sbas_, 0); // Maximum number of SBAS channels
getRosUint("sbas/usage", sbas_usage_, 0);
nh->param("dynamic_model", dynamic_model_, std::string("portable"));
nh->param("fix_mode", fix_mode_, std::string("auto"));
getRosUint("dr_limit", dr_limit_, 0); // Dead reckoning limit
if (enable_ppp_)
ROS_WARN("Warning: PPP is enabled - this is an expert setting.");
checkMin(rate_, 0, "rate");
if(rtcm_ids.size() != rtcm_rates.size())
throw std::runtime_error(std::string("Invalid settings: size of rtcm_ids") +
" must match size of rtcm_rates");
dmodel_ = modelFromString(dynamic_model_);
fmode_ = fixModeFromString(fix_mode_);
nh->param("dat/set", set_dat_, false);
if(set_dat_) {
std::vector<float> shift, rot;
if (!nh->getParam("dat/majA", cfg_dat_.majA)
|| nh->getParam("dat/flat", cfg_dat_.flat)
|| nh->getParam("dat/shift", shift)
|| nh->getParam("dat/rot", rot)
|| nh->getParam("dat/scale", cfg_dat_.scale))
throw std::runtime_error(std::string("dat/set is true, therefore ") +
"dat/majA, dat/flat, dat/shift, dat/rot, & dat/scale must be set");
if(shift.size() != 3 || rot.size() != 3)
throw std::runtime_error(std::string("size of dat/shift & dat/rot ") +
"must be 3");
checkRange(cfg_dat_.majA, 6300000.0, 6500000.0, "dat/majA");
checkRange(cfg_dat_.flat, 0.0, 500.0, "dat/flat");
checkRange(shift, 0.0, 500.0, "dat/shift");
cfg_dat_.dX = shift[0];
cfg_dat_.dY = shift[1];
cfg_dat_.dZ = shift[2];
checkRange(rot, -5000.0, 5000.0, "dat/rot");
cfg_dat_.rotX = rot[0];
cfg_dat_.rotY = rot[1];
cfg_dat_.rotZ = rot[2];
checkRange(cfg_dat_.scale, 0.0, 50.0, "scale");
}
// measurement period [ms]
meas_rate = 1000 / rate_;
}
void UbloxNode::pollMessages(const ros::TimerEvent& event) {
static std::vector<uint8_t> payload(1, 1);
if (enabled["aid_alm"])
gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::ALM, payload);
if (enabled["aid_eph"])
gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::EPH, payload);
if (enabled["aid_hui"])
gps.poll(ublox_msgs::Class::AID, ublox_msgs::Message::AID::HUI);
payload[0]++;
if (payload[0] > 32) {
payload[0] = 1;
}
}
void UbloxNode::printInf(const ublox_msgs::Inf &m, uint8_t id) {
if (id == ublox_msgs::Message::INF::ERROR)
ROS_ERROR_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
else if (id == ublox_msgs::Message::INF::WARNING)
ROS_WARN_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
else if (id == ublox_msgs::Message::INF::DEBUG)
ROS_DEBUG_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
else
ROS_INFO_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
}
void UbloxNode::subscribe() {
ROS_DEBUG("Subscribing to U-Blox messages");
// subscribe messages
nh->param("publish/all", enabled["all"], false);
nh->param("inf/all", enabled["inf"], true);
nh->param("publish/nav/all", enabled["nav"], enabled["all"]);
nh->param("publish/rxm/all", enabled["rxm"], enabled["all"]);
nh->param("publish/aid/all", enabled["aid"], enabled["all"]);
nh->param("publish/mon/all", enabled["mon"], enabled["all"]);
// Nav Messages
nh->param("publish/nav/status", enabled["nav_status"], enabled["nav"]);
if (enabled["nav_status"])
gps.subscribe<ublox_msgs::NavSTATUS>(boost::bind(
publish<ublox_msgs::NavSTATUS>, _1, "navstatus"), kSubscribeRate);
nh->param("publish/nav/posecef", enabled["nav_posecef"], enabled["nav"]);
if (enabled["nav_posecef"])
gps.subscribe<ublox_msgs::NavPOSECEF>(boost::bind(
publish<ublox_msgs::NavPOSECEF>, _1, "navposecef"), kSubscribeRate);
nh->param("publish/nav/clock", enabled["nav_clock"], enabled["nav"]);
if (enabled["nav_clock"])
gps.subscribe<ublox_msgs::NavCLOCK>(boost::bind(
publish<ublox_msgs::NavCLOCK>, _1, "navclock"), kSubscribeRate);
// INF messages
nh->param("inf/debug", enabled["inf_debug"], false);
if (enabled["inf_debug"])
gps.subscribeId<ublox_msgs::Inf>(
boost::bind(&UbloxNode::printInf, this, _1,
ublox_msgs::Message::INF::DEBUG),
ublox_msgs::Message::INF::DEBUG);
nh->param("inf/error", enabled["inf_error"], enabled["inf"]);
if (enabled["inf_error"])
gps.subscribeId<ublox_msgs::Inf>(
boost::bind(&UbloxNode::printInf, this, _1,
ublox_msgs::Message::INF::ERROR),
ublox_msgs::Message::INF::ERROR);
nh->param("inf/notice", enabled["inf_notice"], enabled["inf"]);
if (enabled["inf_notice"])
gps.subscribeId<ublox_msgs::Inf>(
boost::bind(&UbloxNode::printInf, this, _1,
ublox_msgs::Message::INF::NOTICE),
ublox_msgs::Message::INF::NOTICE);
nh->param("inf/test", enabled["inf_test"], enabled["inf"]);
if (enabled["inf_test"])
gps.subscribeId<ublox_msgs::Inf>(
boost::bind(&UbloxNode::printInf, this, _1,
ublox_msgs::Message::INF::TEST),
ublox_msgs::Message::INF::TEST);
nh->param("inf/warning", enabled["inf_warning"], enabled["inf"]);
if (enabled["inf_warning"])
gps.subscribeId<ublox_msgs::Inf>(
boost::bind(&UbloxNode::printInf, this, _1,
ublox_msgs::Message::INF::WARNING),
ublox_msgs::Message::INF::WARNING);
// AID messages
nh->param("publish/aid/alm", enabled["aid_alm"], enabled["aid"]);
if (enabled["aid_alm"])
gps.subscribe<ublox_msgs::AidALM>(boost::bind(
publish<ublox_msgs::AidALM>, _1, "aidalm"), kSubscribeRate);
nh->param("publish/aid/eph", enabled["aid_eph"], enabled["aid"]);
if (enabled["aid_eph"])
gps.subscribe<ublox_msgs::AidEPH>(boost::bind(
publish<ublox_msgs::AidEPH>, _1, "aideph"), kSubscribeRate);
nh->param("publish/aid/hui", enabled["aid_hui"], enabled["aid"]);
if (enabled["aid_hui"])
gps.subscribe<ublox_msgs::AidHUI>(boost::bind(
publish<ublox_msgs::AidHUI>, _1, "aidhui"), kSubscribeRate);
for(int i = 0; i < components_.size(); i++)
components_[i]->subscribe();
}
void UbloxNode::initializeRosDiagnostics() {
if (!nh->hasParam("diagnostic_period"))
nh->setParam("diagnostic_period", kDiagnosticPeriod);
updater.reset(new diagnostic_updater::Updater());
updater->setHardwareID("ublox");
// configure diagnostic updater for frequency
freq_diag = FixDiagnostic(std::string("fix"), kFixFreqTol,
kFixFreqWindow, kTimeStampStatusMin);
for(int i = 0; i < components_.size(); i++)
components_[i]->initializeRosDiagnostics();
}
void UbloxNode::processMonVer() {
ublox_msgs::MonVER monVer;
if (!gps.poll(monVer))
throw std::runtime_error("Failed to poll MonVER & set relevant settings");
ROS_DEBUG("%s, HW VER: %s", monVer.swVersion.c_array(),
monVer.hwVersion.c_array());
// Convert extension to vector of strings
std::vector<std::string> extension;
extension.reserve(monVer.extension.size());
for(std::size_t i = 0; i < monVer.extension.size(); ++i) {
ROS_DEBUG("%s", monVer.extension[i].field.c_array());
// Find the end of the string (null character)
unsigned char* end = std::find(monVer.extension[i].field.begin(),
monVer.extension[i].field.end(), '\0');
extension.push_back(std::string(monVer.extension[i].field.begin(), end));
}
// Get the protocol version
for(std::size_t i = 0; i < extension.size(); ++i) {
std::size_t found = extension[i].find("PROTVER");
if (found != std::string::npos) {
protocol_version_ = ::atof(
extension[i].substr(8, extension[i].size()-8).c_str());
break;
}
}
if (protocol_version_ == 0)
ROS_WARN("Failed to parse MonVER and determine protocol version. %s",
"Defaulting to firmware version 6.");
addFirmwareInterface();
if(protocol_version_ < 18) {
// Final line contains supported GNSS delimited by ;
std::vector<std::string> strs;
if(extension.size() > 0)
boost::split(strs, extension[extension.size()-1], boost::is_any_of(";"));
for(size_t i = 0; i < strs.size(); i++)
supported.insert(strs[i]);
} else {
for(std::size_t i = 0; i < extension.size(); ++i) {
std::vector<std::string> strs;
// Up to 2nd to last line
if(i <= extension.size() - 2) {
boost::split(strs, extension[i], boost::is_any_of("="));
if(strs.size() > 1) {
if (strs[0].compare(std::string("FWVER")) == 0) {
if(strs[1].length() > 8)
addProductInterface(strs[1].substr(0, 3), strs[1].substr(8, 10));
else
addProductInterface(strs[1].substr(0, 3));
continue;
}
}
}
// Last 1-2 lines contain supported GNSS
if(i >= extension.size() - 2) {
boost::split(strs, extension[i], boost::is_any_of(";"));
for(size_t i = 0; i < strs.size(); i++)
supported.insert(strs[i]);
}
}
}
}
bool UbloxNode::configureUblox() {
try {
if (!gps.isInitialized())
throw std::runtime_error("Failed to initialize.");
if (load_.loadMask != 0) {
ROS_DEBUG("Loading u-blox configuration from memory. %u", load_.loadMask);
if (!gps.configure(load_))
throw std::runtime_error(std::string("Failed to load configuration ") +
"from memory");
if (load_.loadMask & load_.MASK_IO_PORT) {
ROS_DEBUG("Loaded I/O configuration from memory, resetting serial %s",
"communications.");
boost::posix_time::seconds wait(kResetWait);
gps.reset(wait);
if (!gps.isConfigured())
throw std::runtime_error(std::string("Failed to reset serial I/O") +
"after loading I/O configurations from device memory.");
}
}
if (set_usb_) {
gps.configUsb(usb_tx_, usb_in_, usb_out_);
}
if (!gps.configRate(meas_rate, nav_rate)) {
std::stringstream ss;
ss << "Failed to set measurement rate to " << meas_rate
<< "ms and navigation rate to " << nav_rate;
throw std::runtime_error(ss.str());
}
// If device doesn't have SBAS, will receive NACK (causes exception)
if(supportsGnss("SBAS")) {
if (!gps.configSbas(enable_sbas_, sbas_usage_, max_sbas_)) {
throw std::runtime_error(std::string("Failed to ") +
((enable_sbas_) ? "enable" : "disable") +
" SBAS.");
}
}
if (!gps.setPpp(enable_ppp_))
throw std::runtime_error(std::string("Failed to ") +
((enable_ppp_) ? "enable" : "disable")
+ " PPP.");
if (!gps.setDynamicModel(dmodel_))
throw std::runtime_error("Failed to set model: " + dynamic_model_ + ".");
if (!gps.setFixMode(fmode_))
throw std::runtime_error("Failed to set fix mode: " + fix_mode_ + ".");
if (!gps.setDeadReckonLimit(dr_limit_)) {
std::stringstream ss;
ss << "Failed to set dead reckoning limit: " << dr_limit_ << ".";
throw std::runtime_error(ss.str());
}
if (set_dat_ && !gps.configure(cfg_dat_))
throw std::runtime_error("Failed to set user-defined datum.");
// Configure each component
for (int i = 0; i < components_.size(); i++) {
if(!components_[i]->configureUblox())
return false;
}
if (save_.saveMask != 0) {
ROS_DEBUG("Saving the u-blox configuration, mask %u, device %u",
save_.saveMask, save_.deviceMask);
if(!gps.configure(save_))
ROS_ERROR("u-blox unable to save configuration to non-volatile memory");
}
} catch (std::exception& e) {
ROS_FATAL("Error configuring u-blox: %s", e.what());
return false;
}
return true;
}
void UbloxNode::configureInf() {
ublox_msgs::CfgINF msg;
// Subscribe to UBX INF messages
ublox_msgs::CfgINF_Block block;
block.protocolID = block.PROTOCOL_ID_UBX;
// Enable desired INF messages on each UBX port
uint8_t mask = (enabled["inf_error"] ? block.INF_MSG_ERROR : 0) |
(enabled["inf_warning"] ? block.INF_MSG_WARNING : 0) |
(enabled["inf_notice"] ? block.INF_MSG_NOTICE : 0) |
(enabled["inf_test"] ? block.INF_MSG_TEST : 0) |
(enabled["inf_debug"] ? block.INF_MSG_DEBUG : 0);
for (int i = 0; i < block.infMsgMask.size(); i++)
block.infMsgMask[i] = mask;
msg.blocks.push_back(block);
// IF NMEA is enabled
if (uart_in_ & ublox_msgs::CfgPRT::PROTO_NMEA) {
ublox_msgs::CfgINF_Block block;
block.protocolID = block.PROTOCOL_ID_NMEA;
// Enable desired INF messages on each NMEA port
for (int i = 0; i < block.infMsgMask.size(); i++)
block.infMsgMask[i] = mask;
msg.blocks.push_back(block);
}
ROS_DEBUG("Configuring INF messages");
if (!gps.configure(msg))
ROS_WARN("Failed to configure INF messages");
}
void UbloxNode::initializeIo() {
boost::smatch match;
if (boost::regex_match(device_, match,
boost::regex("(tcp|udp)://(.+):(\\d+)"))) {
std::string proto(match[1]);
if (proto == "tcp") {
std::string host(match[2]);
std::string port(match[3]);
ROS_INFO("Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
port.c_str());
gps.initializeTcp(host, port);
} else {
throw std::runtime_error("Protocol '" + proto + "' is unsupported");
}
} else {
gps.initializeSerial(device_, baudrate_, uart_in_, uart_out_);
}
}
void UbloxNode::initialize() {
// Params must be set before initializing IO
getRosParams();
initializeIo();
// Must process Mon VER before setting firmware/hardware params
processMonVer();
if(protocol_version_ <= 14) {
if(nh->param("raw_data", false))
components_.push_back(ComponentPtr(new RawDataProduct));
}
// Must set firmware & hardware params before initializing diagnostics
for (int i = 0; i < components_.size(); i++)
components_[i]->getRosParams();
// Do this last
initializeRosDiagnostics();
if (configureUblox()) {
ROS_INFO("U-Blox configured successfully.");
// Subscribe to all U-Blox messages
subscribe();
// Configure INF messages (needs INF params, call after subscribing)
configureInf();
ros::Timer poller;
poller = nh->createTimer(ros::Duration(kPollDuration),
&UbloxNode::pollMessages,
this);
poller.start();
ros::spin();
}
shutdown();
}
void UbloxNode::shutdown() {
if (gps.isInitialized()) {
gps.close();
ROS_INFO("Closed connection to %s.", device_.c_str());
}
}
//
// U-Blox Firmware (all versions)
//
void UbloxFirmware::initializeRosDiagnostics() {
updater->add("fix", this, &UbloxFirmware::fixDiagnostic);
updater->force_update();
}
//
// U-Blox Firmware Version 6
//
UbloxFirmware6::UbloxFirmware6() {}
void UbloxFirmware6::getRosParams() {
// Fix Service type, used when publishing fix status messages
fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS;
nh->param("nmea/set", set_nmea_, false);
if (set_nmea_) {
bool compat, consider;
if (!getRosUint("nmea/version", cfg_nmea_.version))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/version must be set");
if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/num_sv must be set");
if (!nh->getParam("nmea/compat", compat))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/compat must be set");
if (!nh->getParam("nmea/consider", consider))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/consider must be set");
// set flags
cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
// set filter
bool temp;
nh->param("nmea/filter/pos", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
nh->param("nmea/filter/msk_pos", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
nh->param("nmea/filter/time", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
nh->param("nmea/filter/date", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
nh->param("nmea/filter/sbas", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_SBAS_FILT : 0;
nh->param("nmea/filter/track", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
}
}
bool UbloxFirmware6::configureUblox() {
ROS_WARN("ublox_version < 7, ignoring GNSS settings");
if (set_nmea_ && !gps.configure(cfg_nmea_))
throw std::runtime_error("Failed to configure NMEA");
return true;
}
void UbloxFirmware6::subscribe() {
// Whether or not to publish Nav POS LLH (always subscribes)
nh->param("publish/nav/posllh", enabled["nav_posllh"], enabled["nav"]);
nh->param("publish/nav/sol", enabled["nav_sol"], enabled["nav"]);
nh->param("publish/nav/velned", enabled["nav_velned"], enabled["nav"]);
// Always subscribes to these messages, but may not publish to ROS topic
// Subscribe to Nav POSLLH
gps.subscribe<ublox_msgs::NavPOSLLH>(boost::bind(
&UbloxFirmware6::callbackNavPosLlh, this, _1), kSubscribeRate);
gps.subscribe<ublox_msgs::NavSOL>(boost::bind(
// Subscribe to Nav SOL
&UbloxFirmware6::callbackNavSol, this, _1), kSubscribeRate);
// Subscribe to Nav VELNED
gps.subscribe<ublox_msgs::NavVELNED>(boost::bind(
&UbloxFirmware6::callbackNavVelNed, this, _1), kSubscribeRate);
// Subscribe to Nav SVINFO
nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
if (enabled["nav_svinfo"])
gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"),
kNavSvInfoSubscribeRate);
// Subscribe to Mon HW
nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
if (enabled["mon_hw"])
gps.subscribe<ublox_msgs::MonHW6>(boost::bind(
publish<ublox_msgs::MonHW6>, _1, "monhw"), kSubscribeRate);
}
void UbloxFirmware6::fixDiagnostic(
diagnostic_updater::DiagnosticStatusWrapper& stat) {
// Set the diagnostic level based on the fix status
if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_DEAD_RECKONING_ONLY) {
stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
stat.message = "Dead reckoning only";
} else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_2D_FIX) {
stat.level = diagnostic_msgs::DiagnosticStatus::OK;
stat.message = "2D fix";
} else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_3D_FIX) {
stat.level = diagnostic_msgs::DiagnosticStatus::OK;
stat.message = "3D fix";
} else if (last_nav_sol_.gpsFix ==
ublox_msgs::NavSOL::GPS_GPS_DEAD_RECKONING_COMBINED) {
stat.level = diagnostic_msgs::DiagnosticStatus::OK;
stat.message = "GPS and dead reckoning combined";
} else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_TIME_ONLY_FIX) {
stat.level = diagnostic_msgs::DiagnosticStatus::OK;
stat.message = "Time fix only";
}
// If fix is not ok (within DOP & Accuracy Masks), raise the diagnostic level
if (!(last_nav_sol_.flags & ublox_msgs::NavSOL::FLAGS_GPS_FIX_OK)) {
stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
stat.message += ", fix not ok";
}
// Raise diagnostic level to error if no fix
if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_NO_FIX) {
stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
stat.message = "No fix";
}
// Add last fix position
stat.add("iTOW [ms]", last_nav_pos_.iTOW);
stat.add("Latitude [deg]", last_nav_pos_.lat * 1e-7);
stat.add("Longitude [deg]", last_nav_pos_.lon * 1e-7);
stat.add("Altitude [m]", last_nav_pos_.height * 1e-3);
stat.add("Height above MSL [m]", last_nav_pos_.hMSL * 1e-3);
stat.add("Horizontal Accuracy [m]", last_nav_pos_.hAcc * 1e-3);
stat.add("Vertical Accuracy [m]", last_nav_pos_.vAcc * 1e-3);
stat.add("# SVs used", (int)last_nav_sol_.numSV);
}
void UbloxFirmware6::callbackNavPosLlh(const ublox_msgs::NavPOSLLH& m) {
if(enabled["nav_posllh"]) {
static ros::Publisher publisher =
nh->advertise<ublox_msgs::NavPOSLLH>("navposllh", kROSQueueSize);
publisher.publish(m);
}
// Position message
static ros::Publisher fixPublisher =
nh->advertise<sensor_msgs::NavSatFix>("fix", kROSQueueSize);
if (m.iTOW == last_nav_vel_.iTOW)
fix_.header.stamp = velocity_.header.stamp; // use last timestamp
else
fix_.header.stamp = ros::Time::now(); // new timestamp
fix_.header.frame_id = frame_id;
fix_.latitude = m.lat * 1e-7;
fix_.longitude = m.lon * 1e-7;
fix_.altitude = m.height * 1e-3;
if (last_nav_sol_.gpsFix >= last_nav_sol_.GPS_2D_FIX)
fix_.status.status = fix_.status.STATUS_FIX;
else
fix_.status.status = fix_.status.STATUS_NO_FIX;
// Convert from mm to m
const double varH = pow(m.hAcc / 1000.0, 2);
const double varV = pow(m.vAcc / 1000.0, 2);
fix_.position_covariance[0] = varH;
fix_.position_covariance[4] = varH;
fix_.position_covariance[8] = varV;
fix_.position_covariance_type =
sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
fix_.status.service = fix_.status.SERVICE_GPS;
fixPublisher.publish(fix_);
last_nav_pos_ = m;
// update diagnostics
freq_diag.diagnostic->tick(fix_.header.stamp);
updater->update();
}
void UbloxFirmware6::callbackNavVelNed(const ublox_msgs::NavVELNED& m) {
if(enabled["nav_velned"]) {
static ros::Publisher publisher =
nh->advertise<ublox_msgs::NavVELNED>("navvelned", kROSQueueSize);
publisher.publish(m);
}
// Example geometry message
static ros::Publisher velocityPublisher =
nh->advertise<geometry_msgs::TwistWithCovarianceStamped>("fix_velocity",
kROSQueueSize);
if (m.iTOW == last_nav_pos_.iTOW)
velocity_.header.stamp = fix_.header.stamp; // same time as last navposllh
else
velocity_.header.stamp = ros::Time::now(); // create a new timestamp
velocity_.header.frame_id = frame_id;
// convert to XYZ linear velocity
velocity_.twist.twist.linear.x = m.velE / 100.0;
velocity_.twist.twist.linear.y = m.velN / 100.0;
velocity_.twist.twist.linear.z = -m.velD / 100.0;
const double varSpeed = pow(m.sAcc / 100.0, 2);
const int cols = 6;
velocity_.twist.covariance[cols * 0 + 0] = varSpeed;
velocity_.twist.covariance[cols * 1 + 1] = varSpeed;
velocity_.twist.covariance[cols * 2 + 2] = varSpeed;
velocity_.twist.covariance[cols * 3 + 3] = -1; // angular rate unsupported
velocityPublisher.publish(velocity_);
last_nav_vel_ = m;
}
void UbloxFirmware6::callbackNavSol(const ublox_msgs::NavSOL& m) {
if(enabled["nav_sol"]) {
static ros::Publisher publisher =
nh->advertise<ublox_msgs::NavSOL>("navsol", kROSQueueSize);
publisher.publish(m);
}
last_nav_sol_ = m;
}
//
// Ublox Firmware Version 7
//
UbloxFirmware7::UbloxFirmware7() {}
void UbloxFirmware7::getRosParams() {
//
// GNSS configuration
//
// GNSS enable/disable
nh->param("gnss/gps", enable_gps_, true);
nh->param("gnss/glonass", enable_glonass_, false);
nh->param("gnss/qzss", enable_qzss_, false);
getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_,
ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
nh->param("gnss/sbas", enable_sbas_, false);
if(enable_gps_ && !supportsGnss("GPS"))
ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by this device");
if(enable_glonass_ && !supportsGnss("GLO"))
ROS_WARN("gnss/glonass is true, but GLONASS is not %s",
"supported by this device");
if(enable_qzss_ && !supportsGnss("QZSS"))
ROS_WARN("gnss/qzss is true, but QZSS is not supported by this device");
if(enable_sbas_ && !supportsGnss("SBAS"))
ROS_WARN("gnss/sbas is true, but SBAS is not supported by this device");
if(nh->hasParam("gnss/galileo"))
ROS_WARN("ublox_version < 8, ignoring Galileo GNSS Settings");
if(nh->hasParam("gnss/beidou"))
ROS_WARN("ublox_version < 8, ignoring BeiDou Settings");
if(nh->hasParam("gnss/imes"))
ROS_WARN("ublox_version < 8, ignoring IMES GNSS Settings");
// Fix Service type, used when publishing fix status messages
fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS
+ (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS;
//
// NMEA Configuration
//
nh->param("nmea/set", set_nmea_, false);
if (set_nmea_) {
bool compat, consider;
if (!getRosUint("nmea/version", cfg_nmea_.nmeaVersion))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/version must be set");
if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/num_sv must be set");
if (!getRosUint("nmea/sv_numbering", cfg_nmea_.svNumbering))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/sv_numbering must be set");
if (!nh->getParam("nmea/compat", compat))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/compat must be set");
if (!nh->getParam("nmea/consider", consider))
throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
"true, therefore nmea/consider must be set");
// set flags
cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
// set filter
bool temp;
nh->param("nmea/filter/pos", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
nh->param("nmea/filter/msk_pos", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
nh->param("nmea/filter/time", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
nh->param("nmea/filter/date", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
nh->param("nmea/filter/gps_only", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
nh->param("nmea/filter/track", temp, false);
cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
// set gnssToFilter
nh->param("nmea/gnssToFilter/gps", temp, false);
cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
nh->param("nmea/gnssToFilter/sbas", temp, false);
cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
nh->param("nmea/gnssToFilter/qzss", temp, false);
cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
nh->param("nmea/gnssToFilter/glonass", temp, false);
cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
getRosUint("nmea/main_talker_id", cfg_nmea_.mainTalkerId);
getRosUint("nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
}
}
bool UbloxFirmware7::configureUblox() {
/** Configure the GNSS **/
ublox_msgs::CfgGNSS cfgGNSSRead;
if (gps.poll(cfgGNSSRead)) {
ROS_DEBUG("Read GNSS config.");
ROS_DEBUG("Num. tracking channels in hardware: %i", cfgGNSSRead.numTrkChHw);
ROS_DEBUG("Num. tracking channels to use: %i", cfgGNSSRead.numTrkChUse);
} else {
throw std::runtime_error("Failed to read the GNSS config.");
}
ublox_msgs::CfgGNSS cfgGNSSWrite;
cfgGNSSWrite.numConfigBlocks = 1; // do services one by one
cfgGNSSWrite.numTrkChHw = cfgGNSSRead.numTrkChHw;
cfgGNSSWrite.numTrkChUse = cfgGNSSRead.numTrkChUse;
cfgGNSSWrite.msgVer = 0;
// configure GLONASS
if(supportsGnss("GLO")) {
ublox_msgs::CfgGNSS_Block block;
block.gnssId = block.GNSS_ID_GLONASS;
block.resTrkCh = block.RES_TRK_CH_GLONASS;
block.maxTrkCh = block.MAX_TRK_CH_GLONASS;
block.flags = enable_glonass_ ? block.SIG_CFG_GLONASS_L1OF : 0;
cfgGNSSWrite.blocks.push_back(block);
if (!gps.configure(cfgGNSSWrite)) {
throw std::runtime_error(std::string("Failed to ") +
((enable_glonass_) ? "enable" : "disable") +
" GLONASS.");
}
}
if(supportsGnss("QZSS")) {
// configure QZSS
ublox_msgs::CfgGNSS_Block block;
block.gnssId = block.GNSS_ID_QZSS;
block.resTrkCh = block.RES_TRK_CH_QZSS;
block.maxTrkCh = block.MAX_TRK_CH_QZSS;
block.flags = enable_qzss_ ? qzss_sig_cfg_ : 0;
cfgGNSSWrite.blocks[0] = block;
if (!gps.configure(cfgGNSSWrite)) {
throw std::runtime_error(std::string("Failed to ") +
((enable_glonass_) ? "enable" : "disable") +
" QZSS.");
}
}
if(supportsGnss("SBAS")) {
// configure SBAS
ublox_msgs::CfgGNSS_Block block;
block.gnssId = block.GNSS_ID_SBAS;
block.resTrkCh = block.RES_TRK_CH_SBAS;
block.maxTrkCh = block.MAX_TRK_CH_SBAS;
block.flags = enable_sbas_ ? block.SIG_CFG_SBAS_L1CA : 0;
cfgGNSSWrite.blocks[0] = block;
if (!gps.configure(cfgGNSSWrite)) {
throw std::runtime_error(std::string("Failed to ") +
((enable_sbas_) ? "enable" : "disable") +
" SBAS.");
}
}
if(set_nmea_ && !gps.configure(cfg_nmea_))
throw std::runtime_error("Failed to configure NMEA");
return true;
}
void UbloxFirmware7::subscribe() {
// Whether to publish Nav PVT messages to a ROS topic
nh->param("publish/nav/pvt", enabled["nav_pvt"], enabled["nav"]);
// Subscribe to Nav PVT (always does so since fix information is published
// from this)
gps.subscribe<ublox_msgs::NavPVT7>(boost::bind(
&UbloxFirmware7Plus::callbackNavPvt, this, _1),
kSubscribeRate);
// Subscribe to Nav SVINFO
nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
if (enabled["nav_svinfo"])
gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"),
kNavSvInfoSubscribeRate);
// Subscribe to Mon HW
nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
if (enabled["mon_hw"])
gps.subscribe<ublox_msgs::MonHW>(boost::bind(
publish<ublox_msgs::MonHW>, _1, "monhw"), kSubscribeRate);
}
//
// Ublox Version 8
//
UbloxFirmware8::UbloxFirmware8() {}
void UbloxFirmware8::getRosParams() {
// UPD SOS configuration
nh->param("clear_bbr", clear_bbr_, false);
gps.setSaveOnShutdown(nh->param("save_on_shutdown", false));
// GNSS enable/disable
nh->param("gnss/gps", enable_gps_, true);
nh->param("gnss/galileo", enable_galileo_, false);
nh->param("gnss/beidou", enable_beidou_, false);
nh->param("gnss/imes", enable_imes_, false);
nh->param("gnss/glonass", enable_glonass_, false);
nh->param("gnss/qzss", enable_qzss_, false);
nh->param("gnss/sbas", enable_sbas_, false);
// QZSS Signal Configuration
getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_,
ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
if (enable_gps_ && !supportsGnss("GPS"))
ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by %s",
"this device");
if (enable_glonass_ && !supportsGnss("GLO"))
ROS_WARN("gnss/glonass is true, but GLONASS is not supported by %s",
"this device");
if (enable_galileo_ && !supportsGnss("GAL"))
ROS_WARN("gnss/galileo is true, but Galileo GNSS is not supported %s",
"by this device");
if (enable_beidou_ && !supportsGnss("BDS"))
ROS_WARN("gnss/beidou is true, but Beidou GNSS is not supported %s",
"by this device");
if (enable_imes_ && !supportsGnss("IMES"))