|  | 
|  | ROSaicNode () | 
|  | 
|  | ROSaicNode (const rclcpp::NodeOptions &options) | 
|  | 
|  | ~ROSaicNode () | 
|  | 
|  | ~ROSaicNode () | 
|  | 
| 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 () | 
|  | 
|  | 
| bool | getROSParams () | 
|  | Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file.  More... 
 | 
|  | 
| 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) const | 
|  | Gets Euler angles from quaternion message.  More... 
 | 
|  | 
| void | getRPY (const QuaternionMsg &qm, double &roll, double &pitch, double &yaw) const | 
|  | Gets Euler angles from quaternion message.  More... 
 | 
|  | 
| void | getTransform (const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) const | 
|  | Gets transforms from tf2.  More... 
 | 
|  | 
| void | getTransform (const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t) const | 
|  | Gets transforms from tf2.  More... 
 | 
|  | 
| void | sendVelocity (const std::string &velNmea) | 
|  | Send velocity to communication layer (virtual)  More... 
 | 
|  | 
| void | sendVelocity (const std::string &velNmea) | 
|  | Send velocity to communication layer (virtual)  More... 
 | 
|  | 
| void | setup () | 
|  | 
| void | setup () | 
|  | 
| bool | validPeriod (uint32_t period, bool isIns) const | 
|  | Checks if the period has a valid value.  More... 
 | 
|  | 
| bool | validPeriod (uint32_t period, bool isIns) const | 
|  | Checks if the period has a valid value.  More... 
 | 
|  | 
This class represents the ROsaic node, to be extended.. 
Definition at line 83 of file rosaic_node.hpp.