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 ()
 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...
 
void log (LogLevel logLevel, const std::string &s)
 Log function to provide abstraction of ROS loggers. More...
 
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 M >
void publishMessage (const std::string &topic, const M &msg)
 Publishing function. More...
 
void publishTf (const LocalizationUtmMsg &loc)
 Publishing function for tf. More...
 
void registerSubscriber ()
 
 ROSaicNodeBase ()
 
virtual ~ROSaicNodeBase ()
 

Protected Member Functions

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::Odometry::ConstPtr &odo)
 
void callbackTwist (const TwistWithCovarianceStampedMsg::ConstPtr &twist)
 
void processTwist (Timestamp stamp, const geometry_msgs::TwistWithCovariance &twist)
 

Private Attributes

TimestampRos lastTfStamp_
 Last tf stamp. More...
 
ros::Subscriber 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...
 
ros::Subscriber twistSubscriber_
 Twist subscriber. More...
 

Detailed Description

This class is the base class for abstraction.

Definition at line 174 of file typedefs.hpp.

Constructor & Destructor Documentation

◆ ROSaicNodeBase()

ROSaicNodeBase::ROSaicNodeBase ( )
inline

Definition at line 177 of file typedefs.hpp.

◆ ~ROSaicNodeBase()

virtual ROSaicNodeBase::~ROSaicNodeBase ( )
inlinevirtual

Definition at line 179 of file typedefs.hpp.

Member Function Documentation

◆ callbackOdometry()

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

Definition at line 351 of file typedefs.hpp.

◆ callbackTwist()

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

Definition at line 358 of file typedefs.hpp.

◆ getTime()

Timestamp ROSaicNodeBase::getTime ( )
inline

Gets current timestamp.

Returns
Timestamp

Definition at line 259 of file typedefs.hpp.

◆ getUint32Param()

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 200 of file typedefs.hpp.

◆ log()

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

Log function to provide abstraction of ROS loggers.

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

Definition at line 231 of file typedefs.hpp.

◆ param()

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 221 of file typedefs.hpp.

◆ processTwist()

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

Definition at line 365 of file typedefs.hpp.

◆ publishMessage()

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 267 of file typedefs.hpp.

◆ publishTf()

void ROSaicNodeBase::publishTf ( const LocalizationUtmMsg loc)
inline

Publishing function for tf.

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

Definition at line 285 of file typedefs.hpp.

◆ registerSubscriber()

void ROSaicNodeBase::registerSubscriber ( )
inline

Definition at line 181 of file typedefs.hpp.

◆ sendVelocity()

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

Send velocity to communication layer (virtual)

Implemented in rosaic_node::ROSaicNode.

Member Data Documentation

◆ lastTfStamp_

TimestampRos ROSaicNodeBase::lastTfStamp_
private

Last tf stamp.

Definition at line 477 of file typedefs.hpp.

◆ odometrySubscriber_

ros::Subscriber ROSaicNodeBase::odometrySubscriber_
private

Odometry subscriber.

Definition at line 473 of file typedefs.hpp.

◆ pNh_

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

Node handle pointer.

Definition at line 459 of file typedefs.hpp.

◆ queueSize_

uint32_t ROSaicNodeBase::queueSize_ = 1
private

Publisher queue size.

Definition at line 469 of file typedefs.hpp.

◆ settings_

Settings ROSaicNodeBase::settings_
protected

Settings.

Definition at line 461 of file typedefs.hpp.

◆ tf2Publisher_

tf2_ros::TransformBroadcaster ROSaicNodeBase::tf2Publisher_
private

Transform publisher.

Definition at line 471 of file typedefs.hpp.

◆ tfBuffer_

tf2_ros::Buffer ROSaicNodeBase::tfBuffer_
private

tf buffer

Definition at line 479 of file typedefs.hpp.

◆ tfListener_

tf2_ros::TransformListener ROSaicNodeBase::tfListener_
private

Definition at line 481 of file typedefs.hpp.

◆ topicMap_

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

Map of topics and publishers.

Definition at line 467 of file typedefs.hpp.

◆ twistSubscriber_

ros::Subscriber ROSaicNodeBase::twistSubscriber_
private

Twist subscriber.

Definition at line 475 of file typedefs.hpp.


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


septentrio_gnss_driver
Author(s): Tibor Dome
autogenerated on Sat Mar 11 2023 03:12:56