32 #include <Eigen/Geometry> 95 static_cast<uint32_t>(921600));
108 " use either gnss or ins.");
120 static_cast<uint32_t>(1000));
126 "Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
130 static_cast<uint32_t>(1000));
136 "Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
191 if (
getUint32Param(
"ant_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
200 if (
getUint32Param(
"ant_aux1_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
212 bool getConfigFromTf;
213 param(
"get_spatial_config_from_tf", getConfigFromTf,
false);
229 double roll, pitch, yaw;
230 getRPY(T_imu_vehicle.transform.rotation, roll, pitch, yaw);
253 double dy = T_aux1_imu.transform.translation.y -
254 T_ant_imu.transform.translation.y;
255 double dx = T_aux1_imu.transform.translation.x -
256 T_ant_imu.transform.translation.x;
259 double dz = T_aux1_imu.transform.translation.z -
260 T_ant_imu.transform.translation.z;
278 double dy = T_aux1_vehicle.transform.translation.y -
279 T_ant_vehicle.transform.translation.y;
280 double dx = T_aux1_vehicle.transform.translation.x -
281 T_ant_vehicle.transform.translation.x;
284 double dz = T_aux1_vehicle.transform.translation.z -
285 T_ant_vehicle.transform.translation.z;
335 "Pitch angle output by topic /atteuler is a tilt angle rotated by " +
342 "Pitch angle output by topic /pose is a tilt angle rotated by " +
372 "If tf shall be published, ins_use_poi has to be set to true! It is set automatically to true.");
378 for (uint8_t i = 1; i < 4; ++i)
381 std::string ntrip =
"ntrip_" + std::to_string(i);
383 param(
"rtk_settings/" + ntrip +
"/id", ntripSettings.
id, std::string());
384 if (ntripSettings.
id.empty())
387 param(
"rtk_settings/" + ntrip +
"/caster", ntripSettings.
caster,
390 ntripSettings.
caster_port, static_cast<uint32_t>(0));
391 param(
"rtk_settings/" + ntrip +
"/username", ntripSettings.
username,
393 if (!
param(
"rtk_settings/" + ntrip +
"/password", ntripSettings.
password,
398 static_cast<uint32_t>(0));
399 ntripSettings.
password = std::to_string(pwd_tmp);
401 param(
"rtk_settings/" + ntrip +
"/mountpoint", ntripSettings.
mountpoint,
403 param(
"rtk_settings/" + ntrip +
"/version", ntripSettings.
version,
405 param(
"rtk_settings/" + ntrip +
"/tls", ntripSettings.
tls,
false);
406 if (ntripSettings.
tls)
407 param(
"rtk_settings/" + ntrip +
"/fingerprint",
410 std::string(
"auto"));
411 param(
"rtk_settings/" + ntrip +
"/send_gga", ntripSettings.
send_gga,
412 std::string(
"auto"));
415 param(
"rtk_settings/" + ntrip +
"/keep_open", ntripSettings.
keep_open,
true);
420 for (uint8_t i = 1; i < 6; ++i)
423 std::string ips =
"ip_server_" + std::to_string(i);
425 param(
"rtk_settings/" + ips +
"/id", ipSettings.
id, std::string(
""));
426 if (ipSettings.
id.empty())
430 static_cast<uint32_t>(0));
432 std::string(
"auto"));
433 param(
"rtk_settings/" + ips +
"/send_gga", ipSettings.
send_gga,
434 std::string(
"auto"));
437 param(
"rtk_settings/" + ips +
"/keep_open", ipSettings.
keep_open,
true);
442 for (uint8_t i = 1; i < 6; ++i)
445 std::string serial =
"serial_" + std::to_string(i);
447 param(
"rtk_settings/" + serial +
"/port", serialSettings.
port,
449 if (serialSettings.
port.empty())
453 serialSettings.
baud_rate, static_cast<uint32_t>(115200));
454 param(
"rtk_settings/" + serial +
"/rtk_standard",
456 param(
"rtk_settings/" + serial +
"/send_gga", serialSettings.
send_gga,
457 std::string(
"auto"));
458 if (serialSettings.
send_gga.empty())
460 param(
"rtk_settings/" + serial +
"/keep_open", serialSettings.
keep_open,
468 std::string tempString;
471 param(
"ntrip_settings/mode", tempString, std::string(
""));
472 if (tempString !=
"")
475 "Deprecation warning: parameter ntrip_settings/mode has been removed, see README under section rtk_settings.");
476 param(
"ntrip_settings/caster", tempString, std::string(
""));
477 if (tempString !=
"")
480 "Deprecation warning: parameter ntrip_settings/caster has been removed, see README under section rtk_settings.");
481 param(
"ntrip_settings/rx_has_internet", tempBool,
false);
485 "Deprecation warning: parameter ntrip_settings/rx_has_internet has been removed, see README under section rtk_settings.");
486 param(
"ntrip_settings/rx_input_corrections_tcp", tempInt, 0);
490 "Deprecation warning: parameter ntrip_settings/rx_input_corrections_tcp has been removed, see README under section rtk_settings.");
491 param(
"ntrip_settings/rx_input_corrections_serial", tempString,
493 if (tempString !=
"")
496 "Deprecation warning: parameter ntrip_settings/rx_input_corrections_serial has been removed, see README under section rtk_settings.");
505 "AttEuler needs multi-antenna receiver. Multi-antenna setting automatically activated. Deactivate publishing of AttEuler if multi-antenna operation is not available.");
515 bool ins_use_vsm =
false;
521 " -> VSM input will not be used!");
528 static_cast<uint32_t>(0));
529 param(
"ins_vsm/ip_server/keep_open",
533 "external velocity sensor measurements via ip_server are used.");
541 static_cast<uint32_t>(115200));
545 "external velocity sensor measurements via serial are used.");
549 std::vector<bool>());
554 [](
bool v) {
return !v; }))
559 "all elements of ins_vsm/ros/config have been set to false -> VSM input will not be used!");
562 param(
"ins_vsm/ros/variances_by_parameter",
567 std::vector<double>());
572 "ins_vsm/ros/variances has to be of size 3 for var_x, var_y, and var_z -> VSM input will not be used!");
585 "ins_vsm/ros/config of element " +
587 " has been set to be used but its variance is not > 0.0 -> its VSM input will not be used!");
594 [](
bool v) {
return !v; }))
600 "all elements of ins_vsm/ros/config have been set to false due to invalid covariances -> VSM input will not be used!");
604 }
else if (ins_use_vsm)
609 "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!");
627 return ((period == 0) || ((period == 5 && isIns)) || (period == 10) ||
628 (period == 20) || (period == 40) || (period == 50) || (period == 100) ||
629 (period == 200) || (period == 500) || (period == 1000) ||
630 (period == 2000) || (period == 5000) || (period == 10000) ||
631 (period == 15000) || (period == 30000) || (period == 60000) ||
632 (period == 120000) || (period == 300000) || (period == 600000) ||
633 (period == 900000) || (period == 1800000) || (period == 3600000));
637 const std::string& sourceFrame,
652 " to " + targetFrame +
": " + ex.what() +
660 double& pitch,
double& yaw)
662 Eigen::Quaterniond q(qm.w, qm.x, qm.y, qm.z);
663 Eigen::Quaterniond::RotationMatrixType C = q.matrix();
665 roll = std::atan2(C(2, 1), C(2, 2));
666 pitch = std::asin(-C(2, 0));
667 yaw = std::atan2(C(1, 0), C(0, 0));
double theta_z
IMU orientation z-angle.
bool ins_vsm_ros_variances_by_parameter
Whether or not to use variance defined by ROS parameter.
uint32_t polling_period_rest
Polling period for all other SBF blocks and NMEA messages.
std::string vehicle_frame_id
The frame ID of the vehicle frame.
bool keep_open
Wether RTK connections shall be kept open on shutdown.
uint32_t ins_vsm_serial_baud_rate
VSM serial baud rate.
uint32_t ins_vsm_ip_server_port
VSM tcp port.
bool ins_in_gnss_mode
Handle the case when an INS is used in GNSS mode.
std::string id
Id of the NTRIP port.
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
bool tls
Wether to use TLS.
void registerSubscriber()
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
bool publish_basevectorgeod
Whether or not to publish the BaseVectorGeodMsg message.
bool publish_insnavcart
Whether or not to publish the INSNavCartMsg message.
bool publish_attcoveuler
Whether or not to publish the AttCovEulerMsg message.
float delta_e
Marker-to-ARP offset in the eastward direction.
bool publish_tf
Whether or not to publish the tf of the localization.
std::string ins_vsm_ip_server_id
VSM IP server id.
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
std::string hw_flow_control
HW flow control.
bool publish_poscovgeodetic
geometry_msgs::TransformStamped TransformStampedMsg
std::string ins_vsm_serial_port
VSM serial port.
double poi_x
INS POI offset in x-dimension.
void defineMessages()
Defines which Rx messages to read and which ROS messages to publish.
std::string ant_serial_nr
Serial number of your particular Main antenna.
std::string rtk_standard
RTCM version for correction data.
void initializeIO()
Initializes the I/O handling.
RtkSettings rtk_settings
RTK corrections settings.
bool ins_use_poi
INS solution reference point.
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
std::string id
The IP server id.
std::string login_user
Username for login.
std::vector< RtkNtrip > ntrip
std::string ins_vsm_ros_source
VSM source for INS.
double vsm_x
INS velocity sensor lever arm x-offset.
double vsm_y
INS velocity sensor lever arm y-offset.
void log(LogLevel logLevel, const std::string &s)
Log function to provide abstraction of ROS loggers.
double wrapAngle180to180(double angle)
Wraps an angle between -180 and 180 degrees.
std::vector< bool > ins_vsm_ros_config
Whether or not to use individual elements of 3D velocity (v_x, v_y, v_z)
bool getUint32Param(const std::string &name, uint32_t &val, uint32_t defaultVal)
Gets an integer or unsigned integer value from the parameter server.
Settings settings_
Settings.
uint32_t baud_rate
Baud rate of the serial port on which Rx receives the corrections.
std::string fingerprint
Self-signed certificate fingerprint.
bool publish_twist
Whether or not to publish the TwistWithCovarianceStampedMsg message.
void getTransform(const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t)
Gets transforms from tf2.
std::string rx_serial_port
bool publish_gpst
Whether or not to publish the TimeReferenceMsg message with GPST.
double poi_y
INS POI offset in y-dimension.
std::vector< double > ins_vsm_ros_variances
Variances of the 3D velocity (var_x, var_y, var_z)
bool keep_open
Wether RTK connections shall be kept open on shutdown.
bool activate_debug_log
Set logger level to DEBUG.
double ant_lever_x
INS antenna lever arm x-offset.
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
bool param(const std::string &name, T &val, const T &defaultVal)
Gets parameter of type T from the parameter server.
std::string aux1_frame_id
The frame ID of the aux1 antenna.
std::string mountpoint
Mountpoint for NTRIP service.
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
std::string password
Password for NTRIP service.
bool publish_gprmc
Whether or not to publish the RMC message.
double poi_z
INS POI offset in z-dimension.
bool publish_gpgsa
Whether or not to publish the GSA message.
bool ins_vsm_serial_keep_open
Wether VSM shall be kept open om shutdown.
bool getROSParams()
Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file...
float delta_n
Marker-to-ARP offset in the northward direction.
std::string login_password
Password for login.
std::string send_gga
Whether (and at which rate) or not to send GGA to the serial port.
bool publish_poscovcartesian
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
bool publish_basevectorcart
std::string rtk_standard
RTCM version for correction data.
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
double heading_offset
Attitude offset determination in longitudinal direction.
io_comm_rx::Comm_IO IO_
Handles communication with the Rx.
bool publish_gpgga
Whether or not to publish the GGA message.
bool publish_localization
Whether or not to publish the LocalizationMsg message.
geometry_msgs::Quaternion QuaternionMsg
int32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
std::string ant_aux1_serial_nr
Serial number of your particular Aux1 antenna.
std::string septentrio_receiver_type
Septentrio receiver type, either "gnss" or "ins".
bool publish_pvtcartesian
uint32_t baudrate
Baudrate.
bool read_from_pcap
Whether or not we are reading from a PCAP file.
bool publish_velcovgeodetic
double theta_x
IMU orientation x-angle.
bool publish_velsensorsetup
Whether or not to publish the VelSensorSetupMsg message.
std::string device
Device port.
bool lock_utm_zone
Wether the UTM zone of the localization is locked.
void sendVelocity(const std::string &velNmea)
Send velocity to communication layer (virtual)
void sendVelocity(const std::string &velNmea)
Hands over NMEA velocity message over to the send() method of manager_.
bool insert_local_frame
Wether local frame should be inserted into tf.
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
std::string imu_frame_id
The frame ID used in the header of published ROS Imu message.
bool publish_exteventinsnavcart
Whether or not to publish the ExtEventINSNavCartMsg message.
bool publish_gpsfix
Whether or not to publish the GPSFixMsg message.
void configureRx()
Configures Rx: Which SBF/NMEA messages it should output and later correction settings.
std::string vsm_frame_id
The frame ID of the velocity sensor.
bool ins_vsm_ip_server_keep_open
Wether VSM shall be kept open om shutdown.
bool publish_imu
Whether or not to publish the ImuMsg message.
bool publish_imusetup
Whether or not to publish the IMUSetupMsg message.
double ant_lever_y
INS antenna lever arm y-offset.
bool keep_open
Wether RTK connections shall be kept open on shutdown.
float att_std_dev
Attitude deviation mask.
void getRPY(const QuaternionMsg &qm, double &roll, double &pitch, double &yaw)
Gets Euler angles from quaternion message.
float pos_std_dev
Position deviation mask.
std::string ant_aux1_type
bool publish_exteventinsnavgeod
Whether or not to publish the ExtEventINSNavGeodMsg message.
std::vector< RtkSerial > serial
uint32_t caster_port
IP port number of NTRIP caster to connect to.
double vsm_z
INS velocity sensor lever arm z-offset.
double pitch_offset
Attitude offset determination in latitudinal direction.
bool publish_atteuler
Whether or not to publish the AttEulerMsg message.
std::string datum
Datum to be used.
double theta_y
IMU orientation y-angle.
std::string rtk_standard
RTCM version for correction data.
std::unique_ptr< tf2_ros::TransformListener > tfListener_
bool publish_gpgsv
Whether or not to publish the GSV message.
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
std::vector< RtkIpServer > ip_server
bool validPeriod(uint32_t period, bool isIns)
Checks if the period has a valid value.
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
tf2_ros::Buffer tfBuffer_
tf2 buffer and listener
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
#define ROSCONSOLE_DEFAULT_NAME
std::string version
NTRIP version for NTRIP service.
bool use_ros_axis_orientation
ROS axis orientation, body: front-left-up, geographic: ENU.
bool multi_antenna
INS multiantenna.
std::string local_frame_id
Frame id of the local frame to be inserted.
std::string username
Username for NTRIP service.
bool publish_navsatfix
Whether or not to publish the NavSatFixMsg message.
std::string frame_id
The frame ID used in the header of every published ROS message.
float delta_u
Marker-to-ARP offset in the upward direction.
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
The heart of the ROSaic driver: The ROS node that represents it.
double ant_lever_z
INS antenna lever arm z-offset.