YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Localization2D_nws_ros2.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_ROS2_LOCALIZATION2D_NWS_ROS2_H
7#define YARP_ROS2_LOCALIZATION2D_NWS_ROS2_H
8
13#include <yarp/os/Stamp.h>
15
16#include <rclcpp/rclcpp.hpp>
17#include <tf2_msgs/msg/tf_message.hpp>
18#include <nav_msgs/msg/odometry.hpp>
19#include <yarp/math/Math.h>
20
21#include <mutex>
22
38{
39public:
44 Localization2D_nws_ros2& operator=(Localization2D_nws_ros2&&) noexcept = delete;
45 ~Localization2D_nws_ros2() override = default;
46
47 bool attach(yarp::dev::PolyDriver* poly) override;
48 bool detach() override;
49
50 // DeviceDriver
51 bool open(yarp::os::Searchable& config) override;
52 bool close() override;
53
54 // PeriodicThread
55 void run() override;
56
57private:
58 void publish_odometry_on_ROS_topic();
59 void publish_odometry_on_TF_topic();
60
61private:
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;
68
69 std::string m_robot_frame;
70 std::string m_fixed_frame;
71
72
73 double m_stats_time_last;
74 yarp::os::Stamp m_loc_stamp;
75 yarp::os::Stamp m_odom_stamp;
76
77 yarp::dev::OdometryData m_current_odometry;
78 yarp::dev::Nav2D::Map2DLocation m_current_position;
79 yarp::dev::Nav2D::LocalizationStatusEnum m_current_status;
80};
81
82#endif // YARP_ROS2_LOCALIZATION2D_NWS_ROS2_H
This class is the parameters parser for class Localization2D_nws_ros2.
Localization2D_nws_ros2: A localization server which can be wrap multiple algorithms and devices to p...
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
Localization2D_nws_ros2(const Localization2D_nws_ros2 &)=delete
bool detach() override
Detach the object (you must have first called attach).
Localization2D_nws_ros2(Localization2D_nws_ros2 &&) noexcept=delete
bool close() override
Close the DeviceDriver.
void run() override
Loop function.
Interface implemented by all device drivers.
Helper interface for an object that can wrap/or "attach" to a single other device.
An abstraction for a periodic thread.
STL namespace.
The main, catch-all namespace for YARP.
Definition dirs.h:16