6#ifndef YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS
18#include <yarp/rosmsg/geometry_msgs/Twist.h>
36 virtual void onRead (yarp::rosmsg::geometry_msgs::Twist& v)
override;
72 bool close()
override;
75 bool detach()
override;
define control board standard interfaces
contains the definition of a Vector type
MobileBaseVelocityControl_nws_ros: A device which allows a client application to control the velocity...
virtual ~MobileBaseVelocityControl_nws_ros()
bool close() override
Close the DeviceDriver.
commandSubscriber * m_command_subscriber
yarp::os::Node * m_ros_node
MobileBaseVelocityControl_nws_ros()
std::string m_ros_topic_name
std::string m_ros_node_name
yarp::dev::PolyDriver m_subdev
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
yarp::dev::Nav2D::INavigation2DVelocityActions * m_iNavVel
virtual void onRead(yarp::rosmsg::geometry_msgs::Twist &v) override
void init(yarp::dev::Nav2D::INavigation2DVelocityActions *m_iNavVel)
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.
A port specialized for reading data of a constant type published on a topic.