This class is the base class for abstraction.
More...
#include <typedefs.hpp>
|
virtual void | sendVelocity (const std::string &velNmea)=0 |
| Send velocity to communication layer (virtual) More...
|
|
This class is the base class for abstraction.
Definition at line 174 of file typedefs.hpp.
◆ ROSaicNodeBase()
ROSaicNodeBase::ROSaicNodeBase |
( |
| ) |
|
|
inline |
◆ ~ROSaicNodeBase()
virtual ROSaicNodeBase::~ROSaicNodeBase |
( |
| ) |
|
|
inlinevirtual |
◆ callbackOdometry()
void ROSaicNodeBase::callbackOdometry |
( |
const nav_msgs::Odometry::ConstPtr & |
odo | ) |
|
|
inlineprivate |
◆ callbackTwist()
void ROSaicNodeBase::callbackTwist |
( |
const TwistWithCovarianceStampedMsg::ConstPtr & |
twist | ) |
|
|
inlineprivate |
◆ getTime()
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] | name | The key to be used in the parameter server's dictionary |
[out] | val | Storage for the retrieved value, of type U, which can be either unsigned int or int |
[in] | defaultVal | Value 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] | logLevel | Log level |
[in] | s | String 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] | name | The key to be used in the parameter server's dictionary |
[out] | val | Storage for the retrieved value, of type T |
[in] | defaultVal | Value 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 |
◆ publishMessage()
template<typename M >
void ROSaicNodeBase::publishMessage |
( |
const std::string & |
topic, |
|
|
const M & |
msg |
|
) |
| |
|
inline |
Publishing function.
- Parameters
-
[in] | topic | String of topic |
[in] | msg | ROS message to be published |
Definition at line 267 of file typedefs.hpp.
◆ publishTf()
Publishing function for tf.
- Parameters
-
[in] | msg | ROS localization message to be converted to tf |
Definition at line 285 of file typedefs.hpp.
◆ registerSubscriber()
void ROSaicNodeBase::registerSubscriber |
( |
| ) |
|
|
inline |
◆ sendVelocity()
virtual void ROSaicNodeBase::sendVelocity |
( |
const std::string & |
velNmea | ) |
|
|
protectedpure virtual |
◆ lastTfStamp_
◆ odometrySubscriber_
◆ pNh_
◆ queueSize_
uint32_t ROSaicNodeBase::queueSize_ = 1 |
|
private |
◆ settings_
◆ tf2Publisher_
◆ tfBuffer_
◆ tfListener_
◆ topicMap_
std::unordered_map<std::string, ros::Publisher> ROSaicNodeBase::topicMap_ |
|
private |
◆ twistSubscriber_
The documentation for this class was generated from the following file: