YARP
Yet Another Robot Platform
MobileBaseVelocityControl_nws_ros.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: LGPL-2.1-or-later
4 */
5
6#ifndef YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS
8
9#include <yarp/os/Network.h>
12#include <yarp/sig/Vector.h>
13#include <yarp/os/Time.h>
14#include <yarp/os/Subscriber.h>
15#include <yarp/dev/PolyDriver.h>
17#include <yarp/os/Node.h>
20
21#include <mutex>
22#include <string>
23
41 public yarp::os::Subscriber<yarp::rosmsg::geometry_msgs::Twist>
42{
43 public:
45 void deinit();
46
50
52 virtual void onRead (yarp::rosmsg::geometry_msgs::Twist& v) override;
53};
54
58{
59protected:
60 std::string m_ros_node_name = "/mobileBase_VelControl_nws_ros";
61 std::string m_ros_topic_name = "/velocity_input";
64
66
67public:
70
71 /* DeviceDriver methods */
72 bool open(yarp::os::Searchable& config) override;
73 bool close() override;
74
75private:
76 bool detach() override;
77 bool attach(yarp::dev::PolyDriver* driver) override;
78};
79
80#endif // YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_ROS
define control board standard interfaces
contains the definition of a Vector type
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
MobileBaseVelocityControl_nws_ros: A device which allows a client application to control the velocity...
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.
Definition: DeviceDriver.h:30
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.
Definition: WrapperSingle.h:31
The Node class.
Definition: Node.h:23
A base class for nested structures that can be searched.
Definition: Searchable.h:63
A port specialized for reading data of a constant type published on a topic.
Definition: Subscriber.h:22