6#ifndef YARP_ROS2_ODOMETRY2D_NWS_ROS2_H
7#define YARP_ROS2_ODOMETRY2D_NWS_ROS2_H
8#include <rclcpp/rclcpp.hpp>
9#include <nav_msgs/msg/odometry.hpp>
16#include <tf2_msgs/msg/tf_message.hpp>
20#ifndef _USE_MATH_DEFINES
21#define _USE_MATH_DEFINES
24#define DEG2RAD M_PI/180.0
25#define DEFAULT_THREAD_PERIOD 0.02
94 bool close()
override;
111 rclcpp::Node::SharedPtr m_node;
112 rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr m_ros2Publisher_odometry;
113 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_publisher_tf;
This class is the parameters parser for class Odometry2D_nws_ros2.
Odometry2D_nws_ros2: A ros2 nws to get odometry and publish it on a ros2 topic. The attached device m...
void run() override
Loop function.
bool threadInit() override
Initialization method.
bool close() override
Close the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
void threadRelease() override
Release method.
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
Interface implemented by all device drivers.
A container for a device driver.
Helper interface for an object that can wrap/or "attach" to a single other device.
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.