Struct Settings

Struct Documentation

struct Settings

Settings struct.

Public Members

bool activate_debug_log

Set logger level to DEBUG.

std::string device

Device.

device_type::DeviceType device_type

Device type.

std::string device_tcp_ip

TCP IP.

std::string device_tcp_port

TCP port.

uint32_t udp_port

UDP port.

std::string udp_unicast_ip

UDP unicast destination ip.

std::string udp_ip_server

UDP IP server id.

uint32_t tcp_port

TCP port.

std::string tcp_ip_server

TCP IP server id.

std::string file_name

Filename.

std::string login_user

Username for login.

std::string login_password

Password for login.

float reconnect_delay_s

Delay in seconds between reconnection attempts to the connection type specified in the parameter connection_type

uint32_t baudrate

Baudrate.

std::string hw_flow_control

HW flow control.

bool configure_rx
std::string datum

Datum to be used.

uint32_t polling_period_pvt

Polling period for PVT-related SBF blocks.

uint32_t polling_period_rest

Polling period for all other SBF blocks and NMEA messages.

float delta_e

Marker-to-ARP offset in the eastward direction.

float delta_n

Marker-to-ARP offset in the northward direction.

float delta_u

Marker-to-ARP offset in the upward direction.

std::string ant_type

Main antenna type, from the list returned by the command “lstAntennaInfo,

Overview”

std::string ant_aux1_type

Aux1 antenna type, from the list returned by the command “lstAntennaInfo,

Overview”

std::string ant_serial_nr

Serial number of your particular Main antenna.

std::string ant_aux1_serial_nr

Serial number of your particular Aux1 antenna.

bool use_ros_axis_orientation

ROS axis orientation, body: front-left-up, geographic: ENU.

double theta_x

IMU orientation x-angle.

double theta_y

IMU orientation y-angle.

double theta_z

IMU orientation z-angle.

double ant_lever_x

INS antenna lever arm x-offset.

double ant_lever_y

INS antenna lever arm y-offset.

double ant_lever_z

INS antenna lever arm z-offset.

double poi_x

INS POI offset in x-dimension.

double poi_y

INS POI offset in y-dimension.

double poi_z

INS POI offset in z-dimension.

double vsm_x

INS velocity sensor lever arm x-offset.

double vsm_y

INS velocity sensor lever arm y-offset.

double vsm_z

INS velocity sensor lever arm z-offset.

double heading_offset

Attitude offset determination in longitudinal direction.

double pitch_offset

Attitude offset determination in latitudinal direction.

bool multi_antenna

INS multiantenna.

bool ins_use_poi

INS solution reference point.

std::string ins_initial_heading

For heading computation when unit is powered-cycled.

float att_std_dev

Attitude deviation mask.

float pos_std_dev

Position deviation mask.

Rtk rtk

RTK corrections settings.

Osnma osnma

OSNMA settings.

bool publish_gpgga

Whether or not to publish the GGA message.

bool publish_gprmc

Whether or not to publish the RMC message.

bool publish_gpgsa

Whether or not to publish the GSA message.

bool publish_gpgsv

Whether or not to publish the GSV message.

bool publish_measepoch

Whether or not to publish the MeasEpoch message.

bool publish_aimplusstatus

Whether or not to publish the RFStatus and AIMPlusStatus message and diagnostics

bool publish_galauthstatus

Whether or not to publish the GALAuthStatus message and diagnostics.

bool publish_pvtcartesian

Whether or not to publish the PVTCartesianMsg message

bool publish_pvtgeodetic

Whether or not to publish the PVTGeodeticMsg message.

bool publish_basevectorcart

Whether or not to publish the BaseVectorCartMsg message

bool publish_basevectorgeod

Whether or not to publish the BaseVectorGeodMsg message.

bool publish_poscovcartesian

Whether or not to publish the PosCovCartesianMsg message

bool publish_poscovgeodetic

Whether or not to publish the PosCovGeodeticMsg message

bool publish_velcovcartesian

Whether or not to publish the VelCovCartesianMsg message

bool publish_velcovgeodetic

Whether or not to publish the VelCovGeodeticMsg message

bool publish_atteuler

Whether or not to publish the AttEulerMsg message.

bool publish_attcoveuler

Whether or not to publish the AttCovEulerMsg message.

bool publish_insnavcart

Whether or not to publish the INSNavCartMsg message.

bool publish_insnavgeod

Whether or not to publish the INSNavGeodMsg message.

bool publish_imusetup

Whether or not to publish the IMUSetupMsg message.

bool publish_velsensorsetup

Whether or not to publish the VelSensorSetupMsg message.

bool publish_exteventinsnavgeod

Whether or not to publish the ExtEventINSNavGeodMsg message.

bool publish_exteventinsnavcart

Whether or not to publish the ExtEventINSNavCartMsg message.

bool publish_extsensormeas

Whether or not to publish the ExtSensorMeasMsg message.

bool publish_gpst

Whether or not to publish the TimeReferenceMsg message with GPST.

bool publish_navsatfix

Whether or not to publish the NavSatFixMsg message.

bool publish_gpsfix

Whether or not to publish the GpsFixMsg message.

bool publish_pose

Whether or not to publish the PoseWithCovarianceStampedMsg message.

bool publish_diagnostics

Whether or not to publish the DiagnosticArrayMsg message.

bool publish_imu

Whether or not to publish the ImuMsg message.

bool publish_localization

Whether or not to publish the LocalizationMsg message.

bool publish_localization_ecef

Whether or not to publish the LocalizationMsg message.

bool publish_twist

Whether or not to publish the TwistWithCovarianceStampedMsg message.

bool publish_tf

Whether or not to publish the tf of the localization.

bool publish_tf_ecef

Whether or not to publish the tf of the localization.

bool insert_local_frame = false

Wether local frame should be inserted into tf.

std::string local_frame_id

Frame id of the local frame to be inserted.

std::string septentrio_receiver_type

Septentrio receiver type, either “gnss” or “ins”.

bool use_gnss_time

If true, the ROS message headers’ unix time field is constructed from the TOW (in the SBF case) and UTC (in the NMEA case) data. If false, times are constructed within the driver via time(NULL) of the <ctime> library.

bool latency_compensation

Wether processing latency shall be compensated for in ROS timestamp.

std::string frame_id

The frame ID used in the header of every published ROS message.

std::string imu_frame_id

The frame ID used in the header of published ROS Imu message.

std::string poi_frame_id

The frame ID used in the header of published ROS Localization message if poi is used

std::string vsm_frame_id

The frame ID of the velocity sensor.

std::string aux1_frame_id

The frame ID of the aux1 antenna.

std::string vehicle_frame_id

The frame ID of the vehicle frame.

bool lock_utm_zone

Wether the UTM zone of the localization is locked.

int32_t leap_seconds = -128

The number of leap seconds that have been inserted into the UTC time.

bool read_from_sbf_log = false

Whether or not we are reading from an SBF file.

bool read_from_pcap = false

Whether or not we are reading from a PCAP file.

std::string ins_vsm_ros_source

VSM source for INS.

std::vector<bool> ins_vsm_ros_config = {false, false, false}

Whether or not to use individual elements of 3D velocity (v_x, v_y, v_z)

bool ins_vsm_ros_variances_by_parameter = false

Whether or not to use variance defined by ROS parameter.

std::vector<double> ins_vsm_ros_variances = {-1.0, -1.0, -1.0}

Variances of the 3D velocity (var_x, var_y, var_z)

std::string ins_vsm_ip_server_id

VSM IP server id.

uint32_t ins_vsm_ip_server_port

VSM tcp port.

bool ins_vsm_ip_server_keep_open

Wether VSM shall be kept open om shutdown.

std::string ins_vsm_serial_port

VSM serial port.

uint32_t ins_vsm_serial_baud_rate

VSM serial baud rate.

bool ins_vsm_serial_keep_open

Wether VSM shall be kept open om shutdown.