6#ifndef YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS2
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS2
18#include <geometry_msgs/msg/twist.hpp>
19#include <rclcpp/rclcpp.hpp>
30 std::shared_ptr<rclcpp::Node>
node;
58 bool close()
override;
67 rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr m_ros2_subscriber;
68 rclcpp::Node::SharedPtr m_node;
71 void twist_callback(
const geometry_msgs::msg::Twist::SharedPtr msg);
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).
MobileBaseVelocityControl_nws_ros2()=default
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.
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.