YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
MobileBaseVelocityControl_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_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS2
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS2
8
9#include <yarp/os/Network.h>
12#include <yarp/sig/Vector.h>
13#include <yarp/os/Time.h>
14#include <Ros2Spinner.h>
15#include <yarp/dev/PolyDriver.h>
18#include <geometry_msgs/msg/twist.hpp>
19#include <rclcpp/rclcpp.hpp>
21
22#include <mutex>
23#include <string>
24
26{
27public:
29
30 std::shared_ptr<rclcpp::Node> node;
31
33};
34
51{
52
53public:
55
56 /* DeviceDriver methods */
57 bool open(yarp::os::Searchable& config) override;
58 bool close() override;
59
60 bool detach() override;
61 bool attach(yarp::dev::PolyDriver* driver) override;
62
63private:
64 // Spinner
65 Ros2Spinner* m_spinner{nullptr};
66
67 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr m_ros2_subscriber;
68 rclcpp::Node::SharedPtr m_node;
70 yarp::dev::PolyDriver m_subdev;
71 void twist_callback(const geometry_msgs::msg::Twist::SharedPtr msg);
72
73};
74
75#endif // YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS2
define control board standard interfaces
contains the definition of a Vector type
This class is the parameters parser for class MobileBaseVelocityControl_nws_ros2.
MobileBaseVelocityControl_nws_ros2: A device which allows a client application to control the velocit...
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
std::shared_ptr< rclcpp::Node > node
static Ros2InitMobVel & get()
Interface implemented by all device drivers.
A container for a device driver.
Definition PolyDriver.h:23
Helper interface for an object that can wrap/or "attach" to a single other device.
A base class for nested structures that can be searched.
Definition Searchable.h:31