59 #ifndef ROSAIC_NODE_HPP 60 #define ROSAIC_NODE_HPP 116 const std::string& sourceFrame,
138 #endif // for ROSAIC_NODE_HPP This class represents the ROsaic node, to be extended..
geometry_msgs::TransformStamped TransformStampedMsg
Highest-Level view on communication services.
void getTransform(const std::string &targetFrame, const std::string &sourceFrame, TransformStampedMsg &T_s_t)
Gets transforms from tf2.
bool getROSParams()
Gets the node parameters from the ROS Parameter Server, parts of which are specified in a YAML file...
io_comm_rx::Comm_IO IO_
Handles communication with the Rx.
geometry_msgs::Quaternion QuaternionMsg
void sendVelocity(const std::string &velNmea)
Send velocity to communication layer (virtual)
void getRPY(const QuaternionMsg &qm, double &roll, double &pitch, double &yaw)
Gets Euler angles from quaternion message.
This class is the base class for abstraction.
std::unique_ptr< tf2_ros::TransformListener > tfListener_
bool validPeriod(uint32_t period, bool isIns)
Checks if the period has a valid value.
tf2_ros::Buffer tfBuffer_
tf2 buffer and listener
Handles communication with and configuration of the mosaic (and beyond) receiver(s) ...