253 bool insert_local_frame =
false;
259 bool ins_in_gnss_mode =
false;
282 bool read_from_sbf_log =
false;
284 bool read_from_pcap =
false;
288 std::vector<bool> ins_vsm_ros_config = {
false,
false,
false};
290 bool ins_vsm_ros_variances_by_parameter =
false;
292 std::vector<double> ins_vsm_ros_variances = {-1.0, -1.0, -1.0};
double theta_z
IMU orientation z-angle.
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.
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.
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.
std::string hw_flow_control
HW flow control.
bool publish_poscovgeodetic
std::string ins_vsm_serial_port
VSM serial port.
double poi_x
INS POI offset in x-dimension.
std::string ant_serial_nr
Serial number of your particular Main antenna.
std::string rtk_standard
RTCM version for correction data.
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.
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.
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.
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.
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.
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.
bool publish_gpgga
Whether or not to publish the GGA message.
bool publish_localization
Whether or not to publish the LocalizationMsg message.
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 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.
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.
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.
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.
bool publish_gpgsv
Whether or not to publish the GSV message.
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
std::vector< RtkIpServer > ip_server
bool publish_pose
Whether or not to publish the PoseWithCovarianceStampedMsg message.
std::string ins_initial_heading
For heading computation when unit is powered-cycled.
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.
double ant_lever_z
INS antenna lever arm z-offset.