47 bool attach(
yarp::dev::PolyDriver* poly) override;
51 bool open(
yarp::os::Searchable& config) override;
52 bool close() override;
58 void publish_odometry_on_ROS_topic();
59 void publish_odometry_on_TF_topic();
62 yarp::dev::PolyDriver m_driver;
63 yarp::dev::Nav2D::ILocalization2D *m_iLoc =
nullptr;
64 rclcpp::Node::SharedPtr m_node;
65 rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr m_publisher_odom;
66 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_publisher_tf;
67 bool m_isDeviceOwned = false;
69 std::
string m_robot_frame;
70 std::
string m_fixed_frame;
73 double m_stats_time_last;
74 yarp::os::Stamp m_loc_stamp;
75 yarp::os::Stamp m_odom_stamp;
77 yarp::dev::OdometryData m_current_odometry;
78 yarp::dev::Nav2D::Map2DLocation m_current_position;
79 yarp::dev::Nav2D::LocalizationStatusEnum m_current_status;