YARP
Yet Another Robot Platform
MobileBaseVelocityControl_nws_yarp.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_YARP
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_YARP
8
9#include <yarp/os/Network.h>
12#include <yarp/sig/Vector.h>
13#include <yarp/os/Time.h>
14#include <yarp/dev/PolyDriver.h>
19
20#include <mutex>
21#include <string>
22
42class VelocityInputPortProcessor : public yarp::os::BufferedPort<yarp::dev::MobileBaseVelocity>
43{
44public:
45 double m_timeout = 0.1;
47
48public:
50 void onRead(yarp::dev::MobileBaseVelocity& v) override;
51};
52
57{
58protected:
59 std::mutex m_mutex;
62 std::string m_local_name;
63
66
67public:
68
69 /* DeviceDriver methods */
70 bool open(yarp::os::Searchable& config) override;
71 bool close() override;
72 bool detach() override;
73 bool attach(yarp::dev::PolyDriver* driver) override;
74
75public:
76 //* MobileBaseVelocityControlRPC methods*/
77 bool applyVelocityCommandRPC(const double x_vel, const double y_vel, const double theta_vel, const double timeout) override;
79};
80
81#endif // YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWS_YARP
define control board standard interfaces
contains the definition of a Vector type
bool detach() override
Detach the object (you must have first called attach).
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
return_getLastVelocityCommand getLastVelocityCommandRPC() override
yarp::dev::Nav2D::INavigation2DVelocityActions * m_iNavVel
bool applyVelocityCommandRPC(const double x_vel, const double y_vel, const double theta_vel, const double timeout) override
MobileBaseVelocityControl_nws_yarp: A device which allows a client to control the velocity of a mobil...
void onRead(yarp::dev::MobileBaseVelocity &v) override
yarp::dev::Nav2D::INavigation2DVelocityActions * m_iVel
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
A mini-server for performing network communication in the background.
Definition: BufferedPort.h:60
A mini-server for network communication.
Definition: Port.h:46
A base class for nested structures that can be searched.
Definition: Searchable.h:63