32 #include <Eigen/Geometry> 90 static_cast<uint32_t>(18));
109 static_cast<uint32_t>(1000));
118 "Please specify a valid polling period for PVT-related SBF blocks and NMEA messages.");
122 static_cast<uint32_t>(1000));
131 "Please specify a valid polling period for PVT-unrelated SBF blocks and NMEA messages.");
175 if (
getUint32Param(
"ant_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
184 if (
getUint32Param(
"ant_aux1_serial_nr", sn_tmp, static_cast<uint32_t>(0)))
196 bool getConfigFromTf;
197 param(
"get_spatial_config_from_tf", getConfigFromTf,
false);
212 double roll, pitch, yaw;
213 getRPY(T_imu_vehicle.transform.rotation, roll, pitch, yaw);
235 double dy = T_aux1_imu.transform.translation.y - T_ant_imu.transform.translation.y;
236 double dx = T_aux1_imu.transform.translation.x - T_ant_imu.transform.translation.x;
238 double dz = T_aux1_imu.transform.translation.z - T_ant_imu.transform.translation.z;
251 double dy = T_aux1_vehicle.transform.translation.y - T_ant_vehicle.transform.translation.y;
252 double dx = T_aux1_vehicle.transform.translation.x - T_ant_vehicle.transform.translation.x;
254 double dz = T_aux1_vehicle.transform.translation.z - T_ant_vehicle.transform.translation.z;
301 this->
log(
LogLevel::WARN ,
"Pitch angle output by topic /atteuler is a tilt angle rotated by " +
306 this->
log(
LogLevel::WARN ,
"Pitch angle output by topic /pose is a tilt angle rotated by " +
329 this->
log(
LogLevel::ERROR ,
"If tf shall be published, ins_use_poi has to be set to true! It is set automatically to true.");
342 getUint32Param(
"ntrip_settings/password", pwd_tmp, static_cast<uint32_t>(0));
351 static_cast<uint32_t>(28785));
352 param(
"ntrip_settings/rx_input_corrections_serial",
359 this->
log(
LogLevel::WARN ,
"AttEuler needs multi-antenna receiver. Multi-antenna setting automatically activated. Deactivate publishing of AttEuler if multi-antenna operation is not available.");
382 this->
log(
LogLevel::WARN,
"Waiting for transform from " + sourceFrame +
" to " + targetFrame +
": " + ex.what() +
".");
390 Eigen::Quaterniond q(qm.w, qm.x, qm.y, qm.z);
391 Eigen::Quaterniond::RotationMatrixType C = q.matrix();
393 roll = std::atan2(C(2, 1), C(2, 2));
394 pitch = std::asin(-C(2, 0));
395 yaw = std::atan2(C(1, 0), C(0, 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.
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
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.
bool read_from_sbf_log
Whether or not we are reading from an SBF file.
std::string hw_flow_control
HW flow control.
uint32_t leap_seconds
The number of leap seconds that have been inserted into the UTC time.
bool publish_poscovgeodetic
geometry_msgs::TransformStamped TransformStampedMsg
double poi_x
INS POI offset in x-dimension.
uint32_t rx_input_corrections_tcp
std::string ntrip_password
Password for NTRIP service.
std::string rtcm_version
RTCM version for NTRIP service (if Rx does not have internet)
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 rx_input_corrections_serial
void initializeIO()
Initializes the I/O handling.
bool ins_use_poi
INS solution reference point.
std::string login_user
Username for login.
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.
bool getUint32Param(const std::string &name, uint32_t &val, uint32_t defaultVal)
Gets an integer or unsigned integer value from the parameter server.
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.
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.
uint32_t polling_period_pvt
Polling period for PVT-related SBF blocks.
bool publish_insnavgeod
Whether or not to publish the INSNavGeodMsg message.
bool publish_gprmc
Whether or not to publish the RMC message.
bool rx_has_internet
Whether Rx has internet or not.
double poi_z
INS POI offset in z-dimension.
bool publish_gpgsa
Whether or not to publish the GSA message.
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.
bool publish_poscovcartesian
bool publish_measepoch
Whether or not to publish the MeasEpoch message.
Settings settings_
Settings.
bool publish_extsensormeas
Whether or not to publish the ExtSensorMeasMsg message.
double heading_offset
Attitude offset determination in longitudinal direction.
std::string poi_frame_id
The frame ID used in the header of published ROS Localization message if poi is used.
io_comm_rx::Comm_IO IO_
Handles communication with the Rx.
bool publish_gpgga
Whether or not to publish the GGA message.
std::string mountpoint
Mountpoint for NTRIP service.
bool publish_localization
Whether or not to publish the LocalizationMsg message.
geometry_msgs::Quaternion QuaternionMsg
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.
std::string caster
Hostname or IP address of the NTRIP caster to connect to.
bool publish_pvtgeodetic
Whether or not to publish the PVTGeodeticMsg message.
std::string ntrip_mode
Type of NTRIP connection.
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.
std::string send_gga
Whether (and at which rate) or not to send GGA to the NTRIP caster.
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.
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.
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 ntrip_version
NTRIP version for NTRIP service.
std::string datum
Datum to be used.
double theta_y
IMU orientation y-angle.
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)
uint32_t caster_port
IP port number of NTRIP caster to connect to.
bool publish_diagnostics
Whether or not to publish the DiagnosticArrayMsg message.
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 ntrip_username
Username for NTRIP service.
bool use_ros_axis_orientation
ROS axis orientation, body: front-left-up, geographic: ENU.
bool multi_antenna
INS multiantenna.
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.
The heart of the ROSaic driver: The ROS node that represents it.
double ant_lever_z
INS antenna lever arm z-offset.