Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices. More...
#include <node.h>
Public Member Functions | |
bool | configureUblox () |
Configure ADR/UDR settings. | |
void | getRosParams () |
Get the ADR/UDR parameters. | |
void | initializeRosDiagnostics () |
Initialize the ROS diagnostics for the ADR/UDR device. | |
void | subscribe () |
Subscribe to ADR/UDR messages. | |
Protected Member Functions | |
void | callbackEsfMEAS (const ublox_msgs::EsfMEAS &m) |
Protected Attributes | |
sensor_msgs::Imu | imu_ |
sensor_msgs::TimeReference | t_ref_ |
ublox_msgs::TimTM2 | timtm2 |
bool | use_adr_ |
Whether or not to enable dead reckoning. |
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices.
void AdrUdrProduct::callbackEsfMEAS | ( | const ublox_msgs::EsfMEAS & | m | ) | [protected] |
bool AdrUdrProduct::configureUblox | ( | ) | [virtual] |
Configure ADR/UDR settings.
Configure the use_adr setting.
Implements ublox_node::ComponentInterface.
void AdrUdrProduct::getRosParams | ( | ) | [virtual] |
Get the ADR/UDR parameters.
Get the use_adr parameter and check that the nav_rate is 1 Hz.
Implements ublox_node::ComponentInterface.
void ublox_node::AdrUdrProduct::initializeRosDiagnostics | ( | ) | [inline, virtual] |
Initialize the ROS diagnostics for the ADR/UDR device.
Implements ublox_node::ComponentInterface.
void AdrUdrProduct::subscribe | ( | ) | [virtual] |
Subscribe to ADR/UDR messages.
Subscribe to NavATT, ESF and HNR messages based on user parameters.
Implements ublox_node::ComponentInterface.
sensor_msgs::Imu ublox_node::AdrUdrProduct::imu_ [protected] |
sensor_msgs::TimeReference ublox_node::AdrUdrProduct::t_ref_ [protected] |
ublox_msgs::TimTM2 ublox_node::AdrUdrProduct::timtm2 [protected] |
bool ublox_node::AdrUdrProduct::use_adr_ [protected] |