Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ublox_node::AdrUdrProduct Class Reference

Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices. More...

#include <node.h>

Inheritance diagram for ublox_node::AdrUdrProduct:
Inheritance graph
[legend]

Public Member Functions

 AdrUdrProduct (float protocol_version)
 
bool configureUblox ()
 Configure ADR/UDR settings. More...
 
void getRosParams ()
 Get the ADR/UDR parameters. More...
 
void initializeRosDiagnostics ()
 Initialize the ROS diagnostics for the ADR/UDR device. More...
 
void subscribe ()
 Subscribe to ADR/UDR messages. More...
 

Protected Member Functions

void callbackEsfMEAS (const ublox_msgs::EsfMEAS &m)
 

Protected Attributes

sensor_msgs::Imu imu_
 
float protocol_version_
 
sensor_msgs::TimeReference t_ref_
 
ublox_msgs::TimTM2 timtm2
 
bool use_adr_
 Whether or not to enable dead reckoning. More...
 

Detailed Description

Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices.

Definition at line 1096 of file node.h.

Constructor & Destructor Documentation

◆ AdrUdrProduct()

AdrUdrProduct::AdrUdrProduct ( float  protocol_version)

Definition at line 1310 of file node.cpp.

Member Function Documentation

◆ callbackEsfMEAS()

void AdrUdrProduct::callbackEsfMEAS ( const ublox_msgs::EsfMEAS &  m)
protected

Definition at line 1381 of file node.cpp.

◆ configureUblox()

bool AdrUdrProduct::configureUblox ( )
virtual

Configure ADR/UDR settings.

Configure the use_adr setting.

Returns
true if configured correctly, false otherwise

Implements ublox_node::ComponentInterface.

Definition at line 1325 of file node.cpp.

◆ getRosParams()

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.

Definition at line 1317 of file node.cpp.

◆ initializeRosDiagnostics()

void ublox_node::AdrUdrProduct::initializeRosDiagnostics ( )
inlinevirtual

Initialize the ROS diagnostics for the ADR/UDR device.

Todo:
unimplemented

Implements ublox_node::ComponentInterface.

Definition at line 1126 of file node.h.

◆ subscribe()

void AdrUdrProduct::subscribe ( )
virtual

Subscribe to ADR/UDR messages.

Subscribe to NavATT, ESF and HNR messages based on user parameters.

Implements ublox_node::ComponentInterface.

Definition at line 1332 of file node.cpp.

Member Data Documentation

◆ imu_

sensor_msgs::Imu ublox_node::AdrUdrProduct::imu_
protected

Definition at line 1137 of file node.h.

◆ protocol_version_

float ublox_node::AdrUdrProduct::protocol_version_
protected

Definition at line 1134 of file node.h.

◆ t_ref_

sensor_msgs::TimeReference ublox_node::AdrUdrProduct::t_ref_
protected

Definition at line 1138 of file node.h.

◆ timtm2

ublox_msgs::TimTM2 ublox_node::AdrUdrProduct::timtm2
protected

Definition at line 1139 of file node.h.

◆ use_adr_

bool ublox_node::AdrUdrProduct::use_adr_
protected

Whether or not to enable dead reckoning.

Definition at line 1133 of file node.h.


The documentation for this class was generated from the following files:


ublox_gps
Author(s): Johannes Meyer
autogenerated on Wed Dec 7 2022 03:47:53