Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
ROSaicNodeBase Class Referenceabstract

This class is the base class for abstraction. More...

#include <typedefs.hpp>

Inheritance diagram for ROSaicNodeBase:
Inheritance graph
[legend]

Public Member Functions

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 ()
 

Protected Member Functions

virtual void sendVelocity (const std::string &velNmea)=0
 Send velocity to communication layer (virtual) More...
 
virtual void sendVelocity (const std::string &velNmea)=0
 Send velocity to communication layer (virtual) More...
 

Protected Attributes

std::shared_ptr< ros::NodeHandlepNh_
 Node handle pointer. More...
 
Settings settings_
 Settings. More...
 

Private Member Functions

void callbackOdometry (const nav_msgs::msg::Odometry::ConstSharedPtr odo)
 
void callbackOdometry (const nav_msgs::Odometry::ConstPtr &odo)
 
void callbackTwist (const TwistWithCovarianceStampedMsg::ConstPtr &twist)
 
void callbackTwist (const TwistWithCovarianceStampedMsg::ConstSharedPtr twist)
 
void processTwist (Timestamp stamp, const geometry_msgs::msg::TwistWithCovariance &twist)
 
void processTwist (Timestamp stamp, const geometry_msgs::TwistWithCovariance &twist)
 

Private Attributes

Capabilities capabilities_
 
TimestampRos lastTfStamp_
 Last tf stamp. More...
 
Timestamp lastTfStamp_ = 0
 Last tf stamp. More...
 
ros::Subscriber odometrySubscriber_
 Odometry subscriber. More...
 
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr odometrySubscriber_
 Odometry subscriber. More...
 
uint32_t queueSize_ = 1
 Publisher queue size. More...
 
tf2_ros::TransformBroadcaster tf2Publisher_
 Transform publisher. More...
 
tf2_ros::Buffer tfBuffer_
 tf buffer More...
 
tf2_ros::TransformListener tfListener_
 
std::unordered_map< std::string, ros::PublishertopicMap_
 Map of topics and publishers. More...
 
std::unordered_map< std::string, std::any > topicMap_
 Map of topics and publishers. More...
 
ros::Subscriber twistSubscriber_
 Twist subscriber. More...
 
rclcpp::Subscription< TwistWithCovarianceStampedMsg >::SharedPtr twistSubscriber_
 Twist subscriber. More...
 

Detailed Description

This class is the base class for abstraction.

Definition at line 192 of file typedefs.hpp.

Constructor & Destructor Documentation

◆ ROSaicNodeBase() [1/2]

ROSaicNodeBase::ROSaicNodeBase ( const rclcpp::NodeOptions &  options)
inline

Definition at line 195 of file typedefs.hpp.

◆ ~ROSaicNodeBase() [1/2]

ROSaicNodeBase::~ROSaicNodeBase ( )
inline

Definition at line 201 of file typedefs.hpp.

◆ ROSaicNodeBase() [2/2]

ROSaicNodeBase::ROSaicNodeBase ( )
inline

Definition at line 189 of file typedefs_ros1.hpp.

◆ ~ROSaicNodeBase() [2/2]

ROSaicNodeBase::~ROSaicNodeBase ( )
inline

Definition at line 195 of file typedefs_ros1.hpp.

Member Function Documentation

◆ callbackOdometry() [1/2]

void ROSaicNodeBase::callbackOdometry ( const nav_msgs::msg::Odometry::ConstSharedPtr  odo)
inlineprivate

Definition at line 453 of file typedefs.hpp.

◆ callbackOdometry() [2/2]

void ROSaicNodeBase::callbackOdometry ( const nav_msgs::Odometry::ConstPtr &  odo)
inlineprivate

Definition at line 418 of file typedefs_ros1.hpp.

◆ callbackTwist() [1/2]

void ROSaicNodeBase::callbackTwist ( const TwistWithCovarianceStampedMsg::ConstPtr &  twist)
inlineprivate

Definition at line 425 of file typedefs_ros1.hpp.

◆ callbackTwist() [2/2]

void ROSaicNodeBase::callbackTwist ( const TwistWithCovarianceStampedMsg::ConstSharedPtr  twist)
inlineprivate

Definition at line 460 of file typedefs.hpp.

◆ getTime() [1/2]

Timestamp ROSaicNodeBase::getTime ( ) const
inline

Gets current timestamp.

Returns
Timestamp

Definition at line 290 of file typedefs_ros1.hpp.

◆ getTime() [2/2]

Timestamp ROSaicNodeBase::getTime ( ) const
inline

Gets current timestamp.

Returns
Timestamp

Definition at line 314 of file typedefs.hpp.

◆ getUint32Param() [1/2]

bool ROSaicNodeBase::getUint32Param ( const std::string &  name,
uint32_t &  val,
uint32_t  defaultVal 
)
inline

Gets an integer or unsigned integer value from the parameter server.

Parameters
[in]nameThe key to be used in the parameter server's dictionary
[out]valStorage for the retrieved value, of type U, which can be either unsigned int or int
[in]defaultValValue to use if the server doesn't contain this parameter

Definition at line 244 of file typedefs.hpp.

◆ getUint32Param() [2/2]

bool ROSaicNodeBase::getUint32Param ( const std::string &  name,
uint32_t &  val,
uint32_t  defaultVal 
) const
inline

Gets an integer or unsigned integer value from the parameter server.

Parameters
[in]nameThe key to be used in the parameter server's dictionary
[out]valStorage for the retrieved value, of type U, which can be either unsigned int or int
[in]defaultValValue to use if the server doesn't contain this parameter

Definition at line 229 of file typedefs_ros1.hpp.

◆ hasHeading() [1/2]

bool ROSaicNodeBase::hasHeading ( )
inline

Check if Rx has heading.

Definition at line 410 of file typedefs_ros1.hpp.

◆ hasHeading() [2/2]

bool ROSaicNodeBase::hasHeading ( )
inline

Check if Rx has heading.

Definition at line 445 of file typedefs.hpp.

◆ hasImprovedVsmHandling() [1/2]

bool ROSaicNodeBase::hasImprovedVsmHandling ( )
inline

Check if Rx has improved VSM handling.

Definition at line 415 of file typedefs_ros1.hpp.

◆ hasImprovedVsmHandling() [2/2]

bool ROSaicNodeBase::hasImprovedVsmHandling ( )
inline

Check if Rx has improved VSM handling.

Definition at line 450 of file typedefs.hpp.

◆ isIns() [1/2]

bool ROSaicNodeBase::isIns ( )
inline

Check if Rx is INS.

Definition at line 405 of file typedefs_ros1.hpp.

◆ isIns() [2/2]

bool ROSaicNodeBase::isIns ( )
inline

Check if Rx is INS.

Definition at line 440 of file typedefs.hpp.

◆ log() [1/2]

void ROSaicNodeBase::log ( log_level::LogLevel  logLevel,
const std::string &  s 
) const
inline

Log function to provide abstraction of ROS loggers.

Parameters
[in]logLevelLog level
[in]sString to log

Definition at line 262 of file typedefs_ros1.hpp.

◆ log() [2/2]

void ROSaicNodeBase::log ( log_level::LogLevel  logLevel,
const std::string &  s 
) const
inline

Log function to provide abstraction of ROS loggers.

Parameters
[in]logLevelLog level
[in]sString to log

Definition at line 286 of file typedefs.hpp.

◆ ok() [1/2]

bool ROSaicNodeBase::ok ( )
inline

Definition at line 197 of file typedefs_ros1.hpp.

◆ ok() [2/2]

bool ROSaicNodeBase::ok ( )
inline

Definition at line 203 of file typedefs.hpp.

◆ param() [1/2]

template<typename T >
bool ROSaicNodeBase::param ( const std::string &  name,
T &  val,
const T &  defaultVal 
)
inline

Gets parameter of type T from the parameter server.

Parameters
[in]nameThe key to be used in the parameter server's dictionary
[out]valStorage for the retrieved value, of type T
[in]defaultValValue to use if the server doesn't contain this parameter
Returns
True if it could be retrieved, false if not

Definition at line 265 of file typedefs.hpp.

◆ param() [2/2]

template<typename T >
bool ROSaicNodeBase::param ( const std::string &  name,
T &  val,
const T &  defaultVal 
) const
inline

Gets parameter of type T from the parameter server.

Parameters
[in]nameThe key to be used in the parameter server's dictionary
[out]valStorage for the retrieved value, of type T
[in]defaultValValue to use if the server doesn't contain this parameter
Returns
True if it could be retrieved, false if not

Definition at line 252 of file typedefs_ros1.hpp.

◆ processTwist() [1/2]

void ROSaicNodeBase::processTwist ( Timestamp  stamp,
const geometry_msgs::msg::TwistWithCovariance &  twist 
)
inlineprivate

Definition at line 467 of file typedefs.hpp.

◆ processTwist() [2/2]

void ROSaicNodeBase::processTwist ( Timestamp  stamp,
const geometry_msgs::TwistWithCovariance &  twist 
)
inlineprivate

Definition at line 432 of file typedefs_ros1.hpp.

◆ publishMessage() [1/2]

template<typename M >
void ROSaicNodeBase::publishMessage ( const std::string &  topic,
const M &  msg 
)
inline

Publishing function.

Parameters
[in]topicString of topic
[in]msgROS message to be published

Definition at line 298 of file typedefs_ros1.hpp.

◆ publishMessage() [2/2]

template<typename M >
void ROSaicNodeBase::publishMessage ( const std::string &  topic,
const M &  msg 
)
inline

Publishing function.

Parameters
[in]topicString of topic
[in]msgROS message to be published

Definition at line 322 of file typedefs.hpp.

◆ publishTf() [1/2]

void ROSaicNodeBase::publishTf ( const LocalizationMsg loc)
inline

Publishing function for tf.

Parameters
[in]msgROS localization message to be converted to tf

Definition at line 322 of file typedefs_ros1.hpp.

◆ publishTf() [2/2]

void ROSaicNodeBase::publishTf ( const LocalizationMsg loc)
inline

Publishing function for tf.

Parameters
[in]msgROS localization message to be converted to tf

Definition at line 355 of file typedefs.hpp.

◆ registerSubscriber() [1/2]

void ROSaicNodeBase::registerSubscriber ( )
inline

Definition at line 201 of file typedefs_ros1.hpp.

◆ registerSubscriber() [2/2]

void ROSaicNodeBase::registerSubscriber ( )
inline

Definition at line 207 of file typedefs.hpp.

◆ sendVelocity() [1/2]

virtual void ROSaicNodeBase::sendVelocity ( const std::string &  velNmea)
protectedpure virtual

Send velocity to communication layer (virtual)

Implemented in rosaic_node::ROSaicNode, and rosaic_node::ROSaicNode.

◆ sendVelocity() [2/2]

virtual void ROSaicNodeBase::sendVelocity ( const std::string &  velNmea)
protectedpure virtual

Send velocity to communication layer (virtual)

Implemented in rosaic_node::ROSaicNode, and rosaic_node::ROSaicNode.

◆ setHasHeading() [1/2]

void ROSaicNodeBase::setHasHeading ( )
inline

Set has heading to true.

Definition at line 395 of file typedefs_ros1.hpp.

◆ setHasHeading() [2/2]

void ROSaicNodeBase::setHasHeading ( )
inline

Set has heading to true.

Definition at line 430 of file typedefs.hpp.

◆ setImprovedVsmHandling() [1/2]

void ROSaicNodeBase::setImprovedVsmHandling ( )
inline

Set improved VSM handling to true.

Definition at line 400 of file typedefs_ros1.hpp.

◆ setImprovedVsmHandling() [2/2]

void ROSaicNodeBase::setImprovedVsmHandling ( )
inline

Set improved VSM handling to true.

Definition at line 435 of file typedefs.hpp.

◆ setIsIns() [1/2]

void ROSaicNodeBase::setIsIns ( )
inline

Set INS to true.

Definition at line 390 of file typedefs_ros1.hpp.

◆ setIsIns() [2/2]

void ROSaicNodeBase::setIsIns ( )
inline

Set INS to true.

Definition at line 425 of file typedefs.hpp.

◆ settings() [1/2]

const Settings* ROSaicNodeBase::settings ( ) const
inline

Definition at line 199 of file typedefs_ros1.hpp.

◆ settings() [2/2]

const Settings* ROSaicNodeBase::settings ( ) const
inline

Definition at line 205 of file typedefs.hpp.

Member Data Documentation

◆ capabilities_

Capabilities ROSaicNodeBase::capabilities_
private

Definition at line 611 of file typedefs.hpp.

◆ lastTfStamp_ [1/2]

TimestampRos ROSaicNodeBase::lastTfStamp_
private

Last tf stamp.

Definition at line 572 of file typedefs_ros1.hpp.

◆ lastTfStamp_ [2/2]

Timestamp ROSaicNodeBase::lastTfStamp_ = 0
private

Last tf stamp.

Definition at line 605 of file typedefs.hpp.

◆ odometrySubscriber_ [1/2]

ros::Subscriber ROSaicNodeBase::odometrySubscriber_
private

Odometry subscriber.

Definition at line 568 of file typedefs_ros1.hpp.

◆ odometrySubscriber_ [2/2]

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr ROSaicNodeBase::odometrySubscriber_
private

Odometry subscriber.

Definition at line 601 of file typedefs.hpp.

◆ pNh_

std::shared_ptr<ros::NodeHandle> ROSaicNodeBase::pNh_
protected

Node handle pointer.

Definition at line 554 of file typedefs_ros1.hpp.

◆ queueSize_

uint32_t ROSaicNodeBase::queueSize_ = 1
private

Publisher queue size.

Definition at line 597 of file typedefs.hpp.

◆ settings_

Settings ROSaicNodeBase::settings_
protected

Settings.

Definition at line 589 of file typedefs.hpp.

◆ tf2Publisher_

tf2_ros::TransformBroadcaster ROSaicNodeBase::tf2Publisher_
private

Transform publisher.

Definition at line 599 of file typedefs.hpp.

◆ tfBuffer_

tf2_ros::Buffer ROSaicNodeBase::tfBuffer_
private

tf buffer

Definition at line 607 of file typedefs.hpp.

◆ tfListener_

tf2_ros::TransformListener ROSaicNodeBase::tfListener_
private

Definition at line 609 of file typedefs.hpp.

◆ topicMap_ [1/2]

std::unordered_map<std::string, ros::Publisher> ROSaicNodeBase::topicMap_
private

Map of topics and publishers.

Definition at line 562 of file typedefs_ros1.hpp.

◆ topicMap_ [2/2]

std::unordered_map<std::string, std::any> ROSaicNodeBase::topicMap_
private

Map of topics and publishers.

Definition at line 595 of file typedefs.hpp.

◆ twistSubscriber_ [1/2]

ros::Subscriber ROSaicNodeBase::twistSubscriber_
private

Twist subscriber.

Definition at line 570 of file typedefs_ros1.hpp.

◆ twistSubscriber_ [2/2]

rclcpp::Subscription<TwistWithCovarianceStampedMsg>::SharedPtr ROSaicNodeBase::twistSubscriber_
private

Twist subscriber.

Definition at line 603 of file typedefs.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