This class is the base class for abstraction. More...
#include <typedefs.hpp>
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 Settings * | settings () const |
const Settings * | settings () 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::NodeHandle > | pNh_ |
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::Publisher > | topicMap_ |
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... | |
This class is the base class for abstraction.
Definition at line 192 of file typedefs.hpp.
|
inline |
Definition at line 195 of file typedefs.hpp.
|
inline |
Definition at line 201 of file typedefs.hpp.
|
inline |
Definition at line 189 of file typedefs_ros1.hpp.
|
inline |
Definition at line 195 of file typedefs_ros1.hpp.
|
inlineprivate |
Definition at line 453 of file typedefs.hpp.
|
inlineprivate |
Definition at line 418 of file typedefs_ros1.hpp.
|
inlineprivate |
Definition at line 425 of file typedefs_ros1.hpp.
|
inlineprivate |
Definition at line 460 of file typedefs.hpp.
|
inline |
|
inline |
|
inline |
Gets an integer or unsigned integer value from the parameter server.
[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 244 of file typedefs.hpp.
|
inline |
Gets an integer or unsigned integer value from the parameter server.
[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 229 of file typedefs_ros1.hpp.
|
inline |
Check if Rx has heading.
Definition at line 410 of file typedefs_ros1.hpp.
|
inline |
Check if Rx has heading.
Definition at line 445 of file typedefs.hpp.
|
inline |
Check if Rx has improved VSM handling.
Definition at line 415 of file typedefs_ros1.hpp.
|
inline |
Check if Rx has improved VSM handling.
Definition at line 450 of file typedefs.hpp.
|
inline |
Check if Rx is INS.
Definition at line 405 of file typedefs_ros1.hpp.
|
inline |
Check if Rx is INS.
Definition at line 440 of file typedefs.hpp.
|
inline |
Log function to provide abstraction of ROS loggers.
[in] | logLevel | Log level |
[in] | s | String to log |
Definition at line 262 of file typedefs_ros1.hpp.
|
inline |
Log function to provide abstraction of ROS loggers.
[in] | logLevel | Log level |
[in] | s | String to log |
Definition at line 286 of file typedefs.hpp.
|
inline |
Definition at line 197 of file typedefs_ros1.hpp.
|
inline |
Definition at line 203 of file typedefs.hpp.
|
inline |
Gets parameter of type T from the parameter server.
[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 |
Definition at line 265 of file typedefs.hpp.
|
inline |
Gets parameter of type T from the parameter server.
[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 |
Definition at line 252 of file typedefs_ros1.hpp.
|
inlineprivate |
Definition at line 467 of file typedefs.hpp.
|
inlineprivate |
Definition at line 432 of file typedefs_ros1.hpp.
|
inline |
Publishing function.
[in] | topic | String of topic |
[in] | msg | ROS message to be published |
Definition at line 298 of file typedefs_ros1.hpp.
|
inline |
Publishing function.
[in] | topic | String of topic |
[in] | msg | ROS message to be published |
Definition at line 322 of file typedefs.hpp.
|
inline |
Publishing function for tf.
[in] | msg | ROS localization message to be converted to tf |
Definition at line 322 of file typedefs_ros1.hpp.
|
inline |
Publishing function for tf.
[in] | msg | ROS localization message to be converted to tf |
Definition at line 355 of file typedefs.hpp.
|
inline |
Definition at line 201 of file typedefs_ros1.hpp.
|
inline |
Definition at line 207 of file typedefs.hpp.
|
protectedpure virtual |
Send velocity to communication layer (virtual)
Implemented in rosaic_node::ROSaicNode, and rosaic_node::ROSaicNode.
|
protectedpure virtual |
Send velocity to communication layer (virtual)
Implemented in rosaic_node::ROSaicNode, and rosaic_node::ROSaicNode.
|
inline |
Set has heading to true.
Definition at line 395 of file typedefs_ros1.hpp.
|
inline |
Set has heading to true.
Definition at line 430 of file typedefs.hpp.
|
inline |
Set improved VSM handling to true.
Definition at line 400 of file typedefs_ros1.hpp.
|
inline |
Set improved VSM handling to true.
Definition at line 435 of file typedefs.hpp.
|
inline |
Set INS to true.
Definition at line 390 of file typedefs_ros1.hpp.
|
inline |
Set INS to true.
Definition at line 425 of file typedefs.hpp.
|
inline |
Definition at line 199 of file typedefs_ros1.hpp.
|
inline |
Definition at line 205 of file typedefs.hpp.
|
private |
Definition at line 611 of file typedefs.hpp.
|
private |
Last tf stamp.
Definition at line 572 of file typedefs_ros1.hpp.
|
private |
Last tf stamp.
Definition at line 605 of file typedefs.hpp.
|
private |
Odometry subscriber.
Definition at line 568 of file typedefs_ros1.hpp.
|
private |
Odometry subscriber.
Definition at line 601 of file typedefs.hpp.
|
protected |
Node handle pointer.
Definition at line 554 of file typedefs_ros1.hpp.
|
private |
Publisher queue size.
Definition at line 597 of file typedefs.hpp.
|
protected |
Definition at line 589 of file typedefs.hpp.
|
private |
Transform publisher.
Definition at line 599 of file typedefs.hpp.
|
private |
tf buffer
Definition at line 607 of file typedefs.hpp.
|
private |
Definition at line 609 of file typedefs.hpp.
|
private |
Map of topics and publishers.
Definition at line 562 of file typedefs_ros1.hpp.
|
private |
Map of topics and publishers.
Definition at line 595 of file typedefs.hpp.
|
private |
Twist subscriber.
Definition at line 570 of file typedefs_ros1.hpp.
|
private |
Twist subscriber.
Definition at line 603 of file typedefs.hpp.