32 #include <Eigen/Geometry>
69 param(
"use_gnss_time", settings_.use_gnss_time,
true);
70 param(
"latency_compensation", settings_.latency_compensation,
false);
71 param(
"frame_id", settings_.frame_id,
static_cast<std::string
>(
"gnss"));
72 param(
"imu_frame_id", settings_.imu_frame_id,
static_cast<std::string
>(
"imu"));
73 param(
"poi_frame_id", settings_.poi_frame_id,
74 static_cast<std::string
>(
"base_link"));
75 param(
"vsm_frame_id", settings_.vsm_frame_id,
static_cast<std::string
>(
"vsm"));
76 param(
"aux1_frame_id", settings_.aux1_frame_id,
77 static_cast<std::string
>(
"aux1"));
78 param(
"vehicle_frame_id", settings_.vehicle_frame_id, settings_.poi_frame_id);
79 param(
"local_frame_id", settings_.local_frame_id,
80 static_cast<std::string
>(
"odom"));
81 param(
"insert_local_frame", settings_.insert_local_frame,
false);
82 param(
"lock_utm_zone", settings_.lock_utm_zone,
true);
83 param(
"leap_seconds", settings_.leap_seconds, -128);
85 param(
"configure_rx", settings_.configure_rx,
true);
88 param(
"device", settings_.device,
static_cast<std::string
>(
"/dev/ttyACM0"));
89 getUint32Param(
"serial/baudrate", settings_.baudrate,
90 static_cast<uint32_t
>(921600));
91 param(
"serial/hw_flow_control", settings_.hw_flow_control,
92 static_cast<std::string
>(
"off"));
93 getUint32Param(
"stream_device/tcp/port", settings_.tcp_port,
94 static_cast<uint32_t
>(0));
95 param(
"stream_device/tcp/ip_server", settings_.tcp_ip_server,
96 static_cast<std::string
>(
""));
97 getUint32Param(
"stream_device/udp/port", settings_.udp_port,
98 static_cast<uint32_t
>(0));
99 param(
"stream_device/udp/unicast_ip", settings_.udp_unicast_ip,
100 static_cast<std::string
>(
""));
101 param(
"stream_device/udp/ip_server", settings_.udp_ip_server,
102 static_cast<std::string
>(
""));
103 param(
"login/user", settings_.login_user,
static_cast<std::string
>(
""));
104 param(
"login/password", settings_.login_password,
static_cast<std::string
>(
""));
105 settings_.reconnect_delay_s = 2.0f;
106 param(
"receiver_type", settings_.septentrio_receiver_type,
107 static_cast<std::string
>(
"gnss"));
108 if (!((settings_.septentrio_receiver_type ==
"gnss") ||
109 (settings_.septentrio_receiver_type ==
"ins")))
112 settings_.septentrio_receiver_type +
113 " use either gnss or ins.");
117 if (settings_.configure_rx && !settings_.tcp_ip_server.empty() &&
118 !settings_.udp_ip_server.empty())
122 "Both UDP and TCP have been defined to receive data, only TCP will be used. If UDP is intended, leave tcp/ip_server empty.");
126 getUint32Param(
"polling_period/pvt", settings_.polling_period_pvt,
127 static_cast<uint32_t
>(1000));
128 if (!(validPeriod(settings_.polling_period_pvt,
129 settings_.septentrio_receiver_type ==
"ins")))
133 "Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
136 getUint32Param(
"polling_period/rest", settings_.polling_period_rest,
137 static_cast<uint32_t
>(1000));
138 if (!(validPeriod(settings_.polling_period_rest,
139 settings_.septentrio_receiver_type ==
"ins")))
143 "Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
148 param(
"osnma/mode", settings_.osnma.mode, std::string(
"off"));
149 param(
"osnma/ntp_server", settings_.osnma.ntp_server, std::string(
""));
150 param(
"osnma/keep_open", settings_.osnma.keep_open,
true);
153 param(
"multi_antenna", settings_.multi_antenna,
false);
156 param(
"publish/gpst", settings_.publish_gpst,
false);
157 param(
"publish/navsatfix", settings_.publish_navsatfix,
true);
158 param(
"publish/gpsfix", settings_.publish_gpsfix,
false);
159 param(
"publish/pose", settings_.publish_pose,
false);
160 param(
"publish/diagnostics", settings_.publish_diagnostics,
false);
161 param(
"publish/aimplusstatus", settings_.publish_aimplusstatus,
false);
162 param(
"publish/galauthstatus", settings_.publish_galauthstatus,
false);
163 param(
"publish/gpgga", settings_.publish_gpgga,
false);
164 param(
"publish/gprmc", settings_.publish_gprmc,
false);
165 param(
"publish/gpgsa", settings_.publish_gpgsa,
false);
166 param(
"publish/gpgsv", settings_.publish_gpgsv,
false);
167 param(
"publish/measepoch", settings_.publish_measepoch,
false);
168 param(
"publish/pvtcartesian", settings_.publish_pvtcartesian,
false);
169 param(
"publish/pvtgeodetic", settings_.publish_pvtgeodetic,
false);
170 param(
"publish/basevectorcart", settings_.publish_basevectorcart,
false);
171 param(
"publish/basevectorgeod", settings_.publish_basevectorgeod,
false);
172 param(
"publish/poscovcartesian", settings_.publish_poscovcartesian,
false);
173 param(
"publish/poscovgeodetic", settings_.publish_poscovgeodetic,
false);
174 param(
"publish/velcovcartesian", settings_.publish_velcovcartesian,
false);
175 param(
"publish/velcovgeodetic", settings_.publish_velcovgeodetic,
false);
176 param(
"publish/atteuler", settings_.publish_atteuler,
false);
177 param(
"publish/attcoveuler", settings_.publish_attcoveuler,
false);
178 param(
"publish/insnavcart", settings_.publish_insnavcart,
false);
179 param(
"publish/insnavgeod", settings_.publish_insnavgeod,
false);
180 param(
"publish/imusetup", settings_.publish_imusetup,
false);
181 param(
"publish/velsensorsetup", settings_.publish_velsensorsetup,
false);
182 param(
"publish/exteventinsnavgeod", settings_.publish_exteventinsnavgeod,
false);
183 param(
"publish/exteventinsnavcart", settings_.publish_exteventinsnavcart,
false);
184 param(
"publish/extsensormeas", settings_.publish_extsensormeas,
false);
185 param(
"publish/imu", settings_.publish_imu,
false);
186 param(
"publish/localization", settings_.publish_localization,
false);
187 param(
"publish/localization_ecef", settings_.publish_localization_ecef,
false);
188 param(
"publish/twist", settings_.publish_twist,
false);
189 param(
"publish/tf", settings_.publish_tf,
false);
190 param(
"publish/tf_ecef", settings_.publish_tf_ecef,
false);
192 if (settings_.publish_tf && settings_.publish_tf_ecef)
196 "Only one of the tfs may be published at once, just activating tf in ECEF ");
197 settings_.publish_tf =
false;
201 param(
"datum", settings_.datum, std::string(
"Default"));
203 if (settings_.datum ==
"Default")
204 settings_.datum =
"WGS84";
205 param(
"ant_type", settings_.ant_type, std::string(
"Unknown"));
206 param(
"ant_aux1_type", settings_.ant_aux1_type, std::string(
"Unknown"));
207 param(
"ant_serial_nr", settings_.ant_serial_nr, std::string());
208 if (settings_.ant_serial_nr.empty())
211 if (getUint32Param(
"ant_serial_nr", sn_tmp,
static_cast<uint32_t
>(0)))
212 settings_.ant_serial_nr = std::to_string(sn_tmp);
214 settings_.ant_serial_nr =
"Unknown";
216 param(
"ant_aux1_serial_nr", settings_.ant_aux1_serial_nr, std::string());
217 if (settings_.ant_aux1_serial_nr.empty())
220 if (getUint32Param(
"ant_aux1_serial_nr", sn_tmp,
static_cast<uint32_t
>(0)))
221 settings_.ant_aux1_serial_nr = std::to_string(sn_tmp);
223 settings_.ant_aux1_serial_nr =
"Unknown";
225 param(
"poi_to_arp/delta_e", settings_.delta_e, 0.0f);
226 param(
"poi_to_arp/delta_n", settings_.delta_n, 0.0f);
227 param(
"poi_to_arp/delta_u", settings_.delta_u, 0.0f);
229 param(
"use_ros_axis_orientation", settings_.use_ros_axis_orientation,
true);
232 bool getConfigFromTf;
233 param(
"get_spatial_config_from_tf", getConfigFromTf,
false);
236 if (settings_.septentrio_receiver_type ==
"ins")
239 getTransform(settings_.vehicle_frame_id, settings_.imu_frame_id,
242 getTransform(settings_.imu_frame_id, settings_.poi_frame_id, T_poi_imu);
244 getTransform(settings_.imu_frame_id, settings_.vsm_frame_id, T_vsm_imu);
246 getTransform(settings_.imu_frame_id, settings_.frame_id, T_ant_imu);
249 double roll, pitch, yaw;
250 getRPY(T_imu_vehicle.transform.rotation, roll, pitch, yaw);
255 settings_.ant_lever_x = T_ant_imu.transform.translation.x;
256 settings_.ant_lever_y = T_ant_imu.transform.translation.y;
257 settings_.ant_lever_z = T_ant_imu.transform.translation.z;
259 settings_.poi_x = T_poi_imu.transform.translation.x;
260 settings_.poi_y = T_poi_imu.transform.translation.y;
261 settings_.poi_z = T_poi_imu.transform.translation.z;
263 settings_.vsm_x = T_vsm_imu.transform.translation.x;
264 settings_.vsm_y = T_vsm_imu.transform.translation.y;
265 settings_.vsm_z = T_vsm_imu.transform.translation.z;
267 if (settings_.multi_antenna)
270 getTransform(settings_.imu_frame_id, settings_.aux1_frame_id,
273 double dy = T_aux1_imu.transform.translation.y -
274 T_ant_imu.transform.translation.y;
275 double dx = T_aux1_imu.transform.translation.x -
276 T_ant_imu.transform.translation.x;
277 settings_.heading_offset =
279 double dz = T_aux1_imu.transform.translation.z -
280 T_ant_imu.transform.translation.z;
283 settings_.pitch_offset =
287 if ((settings_.septentrio_receiver_type ==
"gnss") &&
288 settings_.multi_antenna)
291 getTransform(settings_.vehicle_frame_id, settings_.frame_id,
294 getTransform(settings_.vehicle_frame_id, settings_.aux1_frame_id,
298 double dy = T_aux1_vehicle.transform.translation.y -
299 T_ant_vehicle.transform.translation.y;
300 double dx = T_aux1_vehicle.transform.translation.x -
301 T_ant_vehicle.transform.translation.x;
302 settings_.heading_offset =
304 double dz = T_aux1_vehicle.transform.translation.z -
305 T_ant_vehicle.transform.translation.z;
313 param(
"ins_spatial_config/imu_orientation/theta_x", settings_.theta_x, 0.0);
314 param(
"ins_spatial_config/imu_orientation/theta_y", settings_.theta_y, 0.0);
315 param(
"ins_spatial_config/imu_orientation/theta_z", settings_.theta_z, 0.0);
317 param(
"ins_spatial_config/ant_lever_arm/x", settings_.ant_lever_x, 0.0);
318 param(
"ins_spatial_config/ant_lever_arm/y", settings_.ant_lever_y, 0.0);
319 param(
"ins_spatial_config/ant_lever_arm/z", settings_.ant_lever_z, 0.0);
321 param(
"ins_spatial_config/poi_lever_arm/delta_x", settings_.poi_x, 0.0);
322 param(
"ins_spatial_config/poi_lever_arm/delta_y", settings_.poi_y, 0.0);
323 param(
"ins_spatial_config/poi_lever_arm/delta_z", settings_.poi_z, 0.0);
325 param(
"ins_spatial_config/vsm_lever_arm/vsm_x", settings_.vsm_x, 0.0);
326 param(
"ins_spatial_config/vsm_lever_arm/vsm_y", settings_.vsm_y, 0.0);
327 param(
"ins_spatial_config/vsm_lever_arm/vsm_z", settings_.vsm_z, 0.0);
329 param(
"att_offset/heading", settings_.heading_offset, 0.0);
330 param(
"att_offset/pitch", settings_.pitch_offset, 0.0);
333 if (settings_.use_ros_axis_orientation)
337 settings_.theta_y *= -1.0;
338 settings_.theta_z *= -1.0;
339 settings_.ant_lever_y *= -1.0;
340 settings_.ant_lever_z *= -1.0;
341 settings_.poi_y *= -1.0;
342 settings_.poi_z *= -1.0;
343 settings_.vsm_y *= -1.0;
344 settings_.vsm_z *= -1.0;
345 settings_.heading_offset *= -1.0;
346 settings_.pitch_offset *= -1.0;
349 if (std::abs(settings_.heading_offset) > std::numeric_limits<double>::epsilon())
351 if (settings_.publish_atteuler)
355 "Pitch angle output by topic /atteuler is a tilt angle rotated by " +
356 std::to_string(settings_.heading_offset) +
".");
358 if (settings_.publish_pose && (settings_.septentrio_receiver_type ==
"gnss"))
362 "Pitch angle output by topic /pose is a tilt angle rotated by " +
363 std::to_string(settings_.heading_offset) +
".");
368 "IMU roll offset: " + std::to_string(settings_.theta_x));
370 "IMU pitch offset: " + std::to_string(settings_.theta_y));
372 "IMU yaw offset: " + std::to_string(settings_.theta_z));
374 "Ant heading offset: " + std::to_string(settings_.heading_offset));
376 "Ant pitch offset: " + std::to_string(settings_.pitch_offset));
379 param(
"ins_initial_heading", settings_.ins_initial_heading, std::string(
"auto"));
382 param(
"ins_std_dev_mask/att_std_dev", settings_.att_std_dev, 5.0f);
383 param(
"ins_std_dev_mask/pos_std_dev", settings_.pos_std_dev, 10.0f);
386 param(
"ins_use_poi", settings_.ins_use_poi,
false);
388 if (settings_.publish_tf && !settings_.ins_use_poi)
392 "If tf shall be published, ins_use_poi has to be set to true! It is set automatically to true.");
393 settings_.ins_use_poi =
true;
398 for (uint8_t i = 1; i < 4; ++i)
401 std::string ntrip =
"ntrip_" + std::to_string(i);
403 param(
"rtk_settings/" + ntrip +
"/id", ntripSettings.
id, std::string());
404 if (ntripSettings.
id.empty())
407 param(
"rtk_settings/" + ntrip +
"/caster", ntripSettings.
caster,
409 getUint32Param(
"rtk_settings/" + ntrip +
"/caster_port",
410 ntripSettings.
caster_port,
static_cast<uint32_t
>(0));
411 param(
"rtk_settings/" + ntrip +
"/username", ntripSettings.
username,
413 if (!
param(
"rtk_settings/" + ntrip +
"/password", ntripSettings.
password,
417 getUint32Param(
"rtk_settings/" + ntrip +
"/password", pwd_tmp,
418 static_cast<uint32_t
>(0));
419 ntripSettings.
password = std::to_string(pwd_tmp);
421 param(
"rtk_settings/" + ntrip +
"/mountpoint", ntripSettings.
mountpoint,
423 param(
"rtk_settings/" + ntrip +
"/version", ntripSettings.
version,
425 param(
"rtk_settings/" + ntrip +
"/tls", ntripSettings.
tls,
false);
426 if (ntripSettings.
tls)
427 param(
"rtk_settings/" + ntrip +
"/fingerprint",
430 std::string(
"auto"));
431 param(
"rtk_settings/" + ntrip +
"/send_gga", ntripSettings.
send_gga,
432 std::string(
"auto"));
435 param(
"rtk_settings/" + ntrip +
"/keep_open", ntripSettings.
keep_open,
true);
437 settings_.rtk.ntrip.push_back(ntripSettings);
440 for (uint8_t i = 1; i < 6; ++i)
443 std::string ips =
"ip_server_" + std::to_string(i);
445 param(
"rtk_settings/" + ips +
"/id", ipSettings.
id, std::string(
""));
446 if (ipSettings.
id.empty())
449 getUint32Param(
"rtk_settings/" + ips +
"/port", ipSettings.
port,
450 static_cast<uint32_t
>(0));
452 std::string(
"auto"));
453 param(
"rtk_settings/" + ips +
"/send_gga", ipSettings.
send_gga,
454 std::string(
"auto"));
457 param(
"rtk_settings/" + ips +
"/keep_open", ipSettings.
keep_open,
true);
459 settings_.rtk.ip_server.push_back(ipSettings);
462 for (uint8_t i = 1; i < 6; ++i)
465 std::string serial =
"serial_" + std::to_string(i);
467 param(
"rtk_settings/" + serial +
"/port", serialSettings.
port,
469 if (serialSettings.
port.empty())
472 getUint32Param(
"rtk_settings/" + serial +
"/baud_rate",
473 serialSettings.
baud_rate,
static_cast<uint32_t
>(115200));
474 param(
"rtk_settings/" + serial +
"/rtk_standard",
476 param(
"rtk_settings/" + serial +
"/send_gga", serialSettings.
send_gga,
477 std::string(
"auto"));
478 if (serialSettings.
send_gga.empty())
480 param(
"rtk_settings/" + serial +
"/keep_open", serialSettings.
keep_open,
483 settings_.rtk.serial.push_back(serialSettings);
488 std::string tempString;
491 param(
"ntrip_settings/mode", tempString, std::string(
""));
492 if (tempString !=
"")
495 "Deprecation warning: parameter ntrip_settings/mode has been removed, see README under section rtk_settings.");
496 param(
"ntrip_settings/caster", tempString, std::string(
""));
497 if (tempString !=
"")
500 "Deprecation warning: parameter ntrip_settings/caster has been removed, see README under section rtk_settings.");
501 param(
"ntrip_settings/rx_has_internet", tempBool,
false);
505 "Deprecation warning: parameter ntrip_settings/rx_has_internet has been removed, see README under section rtk_settings.");
506 param(
"ntrip_settings/rx_input_corrections_tcp", tempInt, 0);
510 "Deprecation warning: parameter ntrip_settings/rx_input_corrections_tcp has been removed, see README under section rtk_settings.");
511 param(
"ntrip_settings/rx_input_corrections_serial", tempString,
513 if (tempString !=
"")
516 "Deprecation warning: parameter ntrip_settings/rx_input_corrections_serial has been removed, see README under section rtk_settings.");
519 if (settings_.publish_atteuler)
521 if (!settings_.multi_antenna)
525 "AttEuler needs multi-antenna receiver. Multi-antenna setting automatically activated. Deactivate publishing of AttEuler if multi-antenna operation is not available.");
526 settings_.multi_antenna =
true;
531 if (settings_.septentrio_receiver_type ==
"ins")
533 param(
"ins_vsm/ros/source", settings_.ins_vsm_ros_source, std::string(
""));
535 bool ins_use_vsm =
false;
536 ins_use_vsm = ((settings_.ins_vsm_ros_source ==
"odometry") ||
537 (settings_.ins_vsm_ros_source ==
"twist"));
538 if (!settings_.ins_vsm_ros_source.empty() && !ins_use_vsm)
540 settings_.ins_vsm_ros_source +
541 " -> VSM input will not be used!");
542 param(
"ins_vsm/ip_server/id", settings_.ins_vsm_ip_server_id,
544 if (!settings_.ins_vsm_ip_server_id.empty())
546 getUint32Param(
"ins_vsm/ip_server/port",
547 settings_.ins_vsm_ip_server_port,
548 static_cast<uint32_t
>(0));
549 param(
"ins_vsm/ip_server/keep_open",
550 settings_.ins_vsm_ip_server_keep_open,
true);
553 "external velocity sensor measurements via ip_server are used.");
556 param(
"ins_vsm/serial/port", settings_.ins_vsm_serial_port, std::string(
""));
557 if (!settings_.ins_vsm_serial_port.empty())
559 getUint32Param(
"ins_vsm/serial/baud_rate",
560 settings_.ins_vsm_serial_baud_rate,
561 static_cast<uint32_t
>(115200));
562 param(
"ins_vsm/serial/keep_open", settings_.ins_vsm_serial_keep_open,
565 "external velocity sensor measurements via serial are used.");
568 param(
"ins_vsm/ros/config", settings_.ins_vsm_ros_config,
569 std::vector<bool>());
570 if (ins_use_vsm && (settings_.ins_vsm_ros_config.size() == 3))
572 if (std::all_of(settings_.ins_vsm_ros_config.begin(),
573 settings_.ins_vsm_ros_config.end(),
574 [](
bool v) { return !v; }))
579 "all elements of ins_vsm/ros/config have been set to false -> VSM input will not be used!");
582 param(
"ins_vsm/ros/variances_by_parameter",
583 settings_.ins_vsm_ros_variances_by_parameter,
false);
584 if (settings_.ins_vsm_ros_variances_by_parameter)
586 param(
"ins_vsm/ros/variances", settings_.ins_vsm_ros_variances,
587 std::vector<double>());
588 if (settings_.ins_vsm_ros_variances.size() != 3)
592 "ins_vsm/ros/variances has to be of size 3 for var_x, var_y, and var_z -> VSM input will not be used!");
594 settings_.ins_vsm_ros_source =
"";
597 for (
size_t i = 0; i < settings_.ins_vsm_ros_config.size();
600 if (settings_.ins_vsm_ros_config[i] &&
601 (settings_.ins_vsm_ros_variances[i] <= 0.0))
605 "ins_vsm/ros/config of element " +
607 " has been set to be used but its variance is not > 0.0 -> its VSM input will not be used!");
608 settings_.ins_vsm_ros_config[i] =
false;
612 if (std::all_of(settings_.ins_vsm_ros_config.begin(),
613 settings_.ins_vsm_ros_config.end(),
614 [](
bool v) { return !v; }))
617 settings_.ins_vsm_ros_source =
"";
620 "all elements of ins_vsm/ros/config have been set to false due to invalid covariances -> VSM input will not be used!");
624 }
else if (ins_use_vsm)
626 settings_.ins_vsm_ros_source =
"";
629 "ins_vsm/ros/config has to be of size 3 to signal wether to use v_x, v_y, and v_z -> VSM input will not be used!");
634 settings_.ins_vsm_ros_source +
636 registerSubscriber();
639 if (!settings_.tcp_ip_server.empty())
641 if (settings_.tcp_ip_server == settings_.udp_ip_server)
644 "tcp/ip_server and udp/ip_server cannot use the same IP server");
645 if (settings_.tcp_ip_server == settings_.ins_vsm_ip_server_id)
648 "tcp/ip_server and ins_vsm/ip_server/id cannot use the same IP server");
649 for (
size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
651 if (settings_.tcp_ip_server == settings_.rtk.ip_server[i].id)
653 "tcp/ip_server and rtk_settings/ip_server_" +
654 std::to_string(i + 1) +
655 "/id cannot use the same IP server");
658 if (!settings_.udp_ip_server.empty())
660 if (settings_.udp_ip_server == settings_.ins_vsm_ip_server_id)
663 "udp/ip_server and ins_vsm/ip_server/id cannot use the same IP server");
664 for (
size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
666 if (settings_.udp_ip_server == settings_.rtk.ip_server[i].id)
668 "udp/ip_server and rtk_settings/ip_server_" +
669 std::to_string(i + 1) +
670 "/id cannot use the same IP server");
673 if (!settings_.ins_vsm_ip_server_id.empty())
675 for (
size_t i = 0; i < settings_.rtk.ip_server.size(); ++i)
677 if (settings_.ins_vsm_ip_server_id == settings_.rtk.ip_server[i].id)
679 "ins_vsm/ip_server/id and rtk_settings/ip_server_" +
680 std::to_string(i + 1) +
681 "/id cannot use the same IP server");
684 if (settings_.rtk.ip_server.size() == 2)
686 if (!settings_.rtk.ip_server[0].id.empty() &&
687 (settings_.rtk.ip_server[0].id == settings_.rtk.ip_server[1].id))
690 "rtk_settings/ip_server_1/id and rtk_settings/ip_server_2/id cannot use the same IP server");
695 if (boost::regex_match(settings_.device, match,
696 boost::regex(
"(tcp)://(.+):(\\d+)")))
698 settings_.device_tcp_ip = match[2];
699 settings_.device_tcp_port = match[3];
701 }
else if (boost::regex_match(settings_.device, match,
702 boost::regex(
"(file_name):(/|(?:/[\\w-]+)+.sbf)")))
704 settings_.read_from_sbf_log =
true;
705 settings_.use_gnss_time =
true;
706 settings_.device = match[2];
708 }
else if (boost::regex_match(
709 settings_.device, match,
710 boost::regex(
"(file_name):(/|(?:/[\\w-]+)+.pcap)")))
712 settings_.read_from_pcap =
true;
713 settings_.use_gnss_time =
true;
714 settings_.device = match[2];
716 }
else if (boost::regex_match(settings_.device, match,
717 boost::regex(
"(serial):(.+)")))
719 std::string proto(match[2]);
721 settings_.device = proto;
724 if (settings_.udp_ip_server.empty() || settings_.configure_rx ||
725 (settings_.ins_vsm_ros_source ==
"odometry") ||
726 (settings_.ins_vsm_ros_source ==
"twist"))
728 std::stringstream ss;
729 ss <<
"Device is unsupported. Perhaps you meant 'tcp://host:port' or 'file_name:xxx.sbf' or 'serial:/path/to/device'?";
743 return ((period == 0) || ((period == 5 && isIns)) || (period == 10) ||
744 (period == 20) || (period == 40) || (period == 50) || (period == 100) ||
745 (period == 200) || (period == 500) || (period == 1000) ||
746 (period == 2000) || (period == 5000) || (period == 10000) ||
747 (period == 15000) || (period == 30000) || (period == 60000) ||
748 (period == 120000) || (period == 300000) || (period == 600000) ||
749 (period == 900000) || (period == 1800000) || (period == 3600000));
753 const std::string& sourceFrame,
762 T_s_t = tfBuffer_.lookupTransform(targetFrame, sourceFrame,
ros::Time(0),
767 this->log(
log_level::WARN,
"Waiting for transform from " + sourceFrame +
768 " to " + targetFrame +
": " + ex.what() +
776 double& pitch,
double& yaw)
const
778 Eigen::Quaterniond q(qm.w, qm.x, qm.y, qm.z);
779 Eigen::Quaterniond::RotationMatrixType C = q.matrix();
781 roll = std::atan2(C(2, 1), C(2, 2));
782 pitch = std::asin(-C(2, 0));
783 yaw = std::atan2(C(1, 0), C(0, 0));
788 IO_.sendVelocity(velNmea);