This class represents the ROsaic node, to be extended.. More...
#include <rosaic_node.hpp>
Public Member Functions | |
ROSaicNode () | |
Private Member Functions | |
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) |
Gets Euler angles from quaternion message. More... | |
void | getTransform (const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) |
Gets transforms from tf2. More... | |
void | sendVelocity (const std::string &velNmea) |
Send velocity to communication layer (virtual) More... | |
bool | validPeriod (uint32_t period, bool isIns) |
Checks if the period has a valid value. More... | |
Private Member Functions inherited from ROSaicNodeBase | |
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 () |
Private Attributes | |
io_comm_rx::Comm_IO | IO_ |
Handles communication with the Rx. More... | |
tf2_ros::Buffer | tfBuffer_ |
tf2 buffer and listener More... | |
std::unique_ptr< tf2_ros::TransformListener > | tfListener_ |
Private Attributes inherited from ROSaicNodeBase | |
std::shared_ptr< ros::NodeHandle > | pNh_ |
Node handle pointer. More... | |
Settings | settings_ |
Settings. More... | |
This class represents the ROsaic node, to be extended..
Definition at line 86 of file rosaic_node.hpp.
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 41 of file rosaic_node.cpp.
|
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 78 of file rosaic_node.cpp.
|
private |
Gets Euler angles from quaternion message.
[in] | qm | quaternion message |
[out] | roll | roll angle |
[out] | pitch | pitch angle |
[out] | yaw | yaw angle |
Definition at line 659 of file rosaic_node.cpp.
|
private |
Gets transforms from tf2.
[in] | targetFrame | traget frame id |
[in] | sourceFrame | source frame id |
[out] | T_s_t | transfrom from source to target |
Definition at line 636 of file rosaic_node.cpp.
|
privatevirtual |
Send velocity to communication layer (virtual)
Implements ROSaicNodeBase.
Definition at line 670 of file rosaic_node.cpp.
|
private |
Checks if the period has a valid value.
[in] | period | period [ms] |
[in] | isIns | wether recevier is an INS |
Definition at line 625 of file rosaic_node.cpp.
|
private |
Handles communication with the Rx.
Definition at line 131 of file rosaic_node.hpp.
|
private |
tf2 buffer and listener
Definition at line 133 of file rosaic_node.hpp.
|
private |
Definition at line 134 of file rosaic_node.hpp.