Public Member Functions | Private Member Functions | Private Attributes | List of all members
rosaic_node::ROSaicNode Class Reference

This class represents the ROsaic node, to be extended.. More...

#include <rosaic_node.hpp>

Inheritance diagram for rosaic_node::ROSaicNode:
Inheritance graph
[legend]

Public Member Functions

 ROSaicNode ()
 
 ROSaicNode (const rclcpp::NodeOptions &options)
 
 ~ROSaicNode ()
 
 ~ROSaicNode ()
 
- Public Member Functions inherited from ROSaicNodeBase
Timestamp getTime () const
 Gets current timestamp. More...
 
Timestamp getTime () const
 Gets current timestamp. More...
 
bool getUint32Param (const std::string &name, uint32_t &val, uint32_t defaultVal)
 Gets an integer or unsigned integer value from the parameter server. More...
 
bool getUint32Param (const std::string &name, uint32_t &val, uint32_t defaultVal) const
 Gets an integer or unsigned integer value from the parameter server. More...
 
bool hasHeading ()
 Check if Rx has heading. More...
 
bool hasHeading ()
 Check if Rx has heading. More...
 
bool hasImprovedVsmHandling ()
 Check if Rx has improved VSM handling. More...
 
bool hasImprovedVsmHandling ()
 Check if Rx has improved VSM handling. More...
 
bool isIns ()
 Check if Rx is INS. More...
 
bool isIns ()
 Check if Rx is INS. More...
 
void log (log_level::LogLevel logLevel, const std::string &s) const
 Log function to provide abstraction of ROS loggers. More...
 
void log (log_level::LogLevel logLevel, const std::string &s) const
 Log function to provide abstraction of ROS loggers. More...
 
bool ok ()
 
bool ok ()
 
template<typename T >
bool param (const std::string &name, T &val, const T &defaultVal)
 Gets parameter of type T from the parameter server. More...
 
template<typename T >
bool param (const std::string &name, T &val, const T &defaultVal) const
 Gets parameter of type T from the parameter server. More...
 
template<typename M >
void publishMessage (const std::string &topic, const M &msg)
 Publishing function. More...
 
template<typename M >
void publishMessage (const std::string &topic, const M &msg)
 Publishing function. More...
 
void publishTf (const LocalizationMsg &loc)
 Publishing function for tf. More...
 
void publishTf (const LocalizationMsg &loc)
 Publishing function for tf. More...
 
void registerSubscriber ()
 
void registerSubscriber ()
 
 ROSaicNodeBase ()
 
 ROSaicNodeBase (const rclcpp::NodeOptions &options)
 
void setHasHeading ()
 Set has heading to true. More...
 
void setHasHeading ()
 Set has heading to true. More...
 
void setImprovedVsmHandling ()
 Set improved VSM handling to true. More...
 
void setImprovedVsmHandling ()
 Set improved VSM handling to true. More...
 
void setIsIns ()
 Set INS to true. More...
 
void setIsIns ()
 Set INS to true. More...
 
const Settingssettings () const
 
const Settingssettings () const
 
 ~ROSaicNodeBase ()
 
 ~ROSaicNodeBase ()
 

Private Member Functions

bool getROSParams ()
 Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file. More...
 
bool getROSParams ()
 Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file. More...
 
void getRPY (const QuaternionMsg &qm, double &roll, double &pitch, double &yaw) const
 Gets Euler angles from quaternion message. More...
 
void getRPY (const QuaternionMsg &qm, double &roll, double &pitch, double &yaw) const
 Gets Euler angles from quaternion message. More...
 
void getTransform (const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) const
 Gets transforms from tf2. More...
 
void getTransform (const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) const
 Gets transforms from tf2. More...
 
void sendVelocity (const std::string &velNmea)
 Send velocity to communication layer (virtual) More...
 
void sendVelocity (const std::string &velNmea)
 Send velocity to communication layer (virtual) More...
 
void setup ()
 
void setup ()
 
bool validPeriod (uint32_t period, bool isIns) const
 Checks if the period has a valid value. More...
 
bool validPeriod (uint32_t period, bool isIns) const
 Checks if the period has a valid value. More...
 

Private Attributes

io::CommunicationCore IO_
 Handles communication with the Rx. More...
 
std::thread setupThread_
 
tf2_ros::Buffer tfBuffer_
 tf2 buffer and listener More...
 
std::unique_ptr< tf2_ros::TransformListenertfListener_
 

Additional Inherited Members

- Protected Attributes inherited from ROSaicNodeBase
std::shared_ptr< ros::NodeHandlepNh_
 Node handle pointer. More...
 
Settings settings_
 Settings. More...
 

Detailed Description

This class represents the ROsaic node, to be extended..

Definition at line 83 of file rosaic_node.hpp.

Constructor & Destructor Documentation

◆ ROSaicNode() [1/2]

rosaic_node::ROSaicNode::ROSaicNode ( const rclcpp::NodeOptions &  options)

The constructor initializes and runs the ROSaic node, if everything works fine. It loads the user-defined ROS parameters, subscribes to Rx messages, and publishes requested ROS messages...

Definition at line 43 of file rosaic_node.cpp.

◆ ~ROSaicNode() [1/2]

rosaic_node::ROSaicNode::~ROSaicNode ( )

Definition at line 72 of file rosaic_node.cpp.

◆ ROSaicNode() [2/2]

rosaic_node::ROSaicNode::ROSaicNode ( )

The constructor initializes and runs the ROSaic node, if everything works fine. It loads the user-defined ROS parameters, subscribes to Rx messages, and publishes requested ROS messages...

Definition at line 43 of file rosaic_node_ros1.cpp.

◆ ~ROSaicNode() [2/2]

rosaic_node::ROSaicNode::~ROSaicNode ( )

Member Function Documentation

◆ getROSParams() [1/2]

bool rosaic_node::ROSaicNode::getROSParams ( )
private

Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file.

The other ROSaic parameters are specified via the command line.

Definition at line 85 of file rosaic_node.cpp.

◆ getROSParams() [2/2]

bool rosaic_node::ROSaicNode::getROSParams ( )
private

Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file.

The other ROSaic parameters are specified via the command line.

◆ getRPY() [1/2]

void rosaic_node::ROSaicNode::getRPY ( const QuaternionMsg qm,
double &  roll,
double &  pitch,
double &  yaw 
) const
private

Gets Euler angles from quaternion message.

Parameters
[in]qmquaternion message
[out]rollroll angle
[out]pitchpitch angle
[out]yawyaw angle

Definition at line 814 of file rosaic_node.cpp.

◆ getRPY() [2/2]

void rosaic_node::ROSaicNode::getRPY ( const QuaternionMsg qm,
double &  roll,
double &  pitch,
double &  yaw 
) const
private

Gets Euler angles from quaternion message.

Parameters
[in]qmquaternion message
[out]rollroll angle
[out]pitchpitch angle
[out]yawyaw angle

◆ getTransform() [1/2]

void rosaic_node::ROSaicNode::getTransform ( const std::string &  targetFrame,
const std::string &  sourceFrame,
TransformStampedMsg T_s_t 
) const
private

Gets transforms from tf2.

Parameters
[in]targetFrametraget frame id
[in]sourceFramesource frame id
[out]T_s_ttransfrom from source to target

Definition at line 789 of file rosaic_node.cpp.

◆ getTransform() [2/2]

void rosaic_node::ROSaicNode::getTransform ( const std::string &  targetFrame,
const std::string &  sourceFrame,
TransformStampedMsg T_s_t 
) const
private

Gets transforms from tf2.

Parameters
[in]targetFrametraget frame id
[in]sourceFramesource frame id
[out]T_s_ttransfrom from source to target

◆ sendVelocity() [1/2]

void rosaic_node::ROSaicNode::sendVelocity ( const std::string &  velNmea)
privatevirtual

Send velocity to communication layer (virtual)

Implements ROSaicNodeBase.

Definition at line 825 of file rosaic_node.cpp.

◆ sendVelocity() [2/2]

void rosaic_node::ROSaicNode::sendVelocity ( const std::string &  velNmea)
privatevirtual

Send velocity to communication layer (virtual)

Implements ROSaicNodeBase.

◆ setup() [1/2]

void rosaic_node::ROSaicNode::setup ( )
private

Definition at line 79 of file rosaic_node.cpp.

◆ setup() [2/2]

void rosaic_node::ROSaicNode::setup ( )
private

◆ validPeriod() [1/2]

bool rosaic_node::ROSaicNode::validPeriod ( uint32_t  period,
bool  isIns 
) const
private

Checks if the period has a valid value.

Parameters
[in]periodperiod [ms]
[in]isInswether recevier is an INS
Returns
wether the period is valid

Definition at line 777 of file rosaic_node.cpp.

◆ validPeriod() [2/2]

bool rosaic_node::ROSaicNode::validPeriod ( uint32_t  period,
bool  isIns 
) const
private

Checks if the period has a valid value.

Parameters
[in]periodperiod [ms]
[in]isInswether recevier is an INS
Returns
wether the period is valid

Member Data Documentation

◆ IO_

io::CommunicationCore rosaic_node::ROSaicNode::IO_
private

Handles communication with the Rx.

Definition at line 131 of file rosaic_node.hpp.

◆ setupThread_

std::thread rosaic_node::ROSaicNode::setupThread_
private

Definition at line 136 of file rosaic_node.hpp.

◆ tfBuffer_

tf2_ros::Buffer rosaic_node::ROSaicNode::tfBuffer_
private

tf2 buffer and listener

Definition at line 133 of file rosaic_node.hpp.

◆ tfListener_

std::unique_ptr< tf2_ros::TransformListener > rosaic_node::ROSaicNode::tfListener_
private

Definition at line 134 of file rosaic_node.hpp.


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


septentrio_gnss_driver
Author(s): Tibor Dome, Thomas Emter
autogenerated on Sat May 10 2025 03:03:11