6#ifndef YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWC_YARP
7#define YARP_DEV_MOBILEBASEVELOCITYCONTROL_NWC_YARP
52 bool close()
override;
55 bool applyVelocityCommand(
double x_vel,
double y_vel,
double theta_vel,
double timeout = 0.1)
override;
define control board standard interfaces
contains the definition of a Vector type
MobileBaseVelocityControl_nwc_yarp: A device which connects to MobileBaseVelocityControl_nws_yarp to ...
std::string m_server_name
bool close() override
Close the DeviceDriver.
yarp::os::Port m_rpc_port
bool applyVelocityCommand(double x_vel, double y_vel, double theta_vel, double timeout=0.1) override
Apply a velocity command.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool getLastVelocityCommand(double &x_vel, double &y_vel, double &theta_vel) override
Returns the last applied velocity command.
MobileBaseVelocityControlRPC m_RPC
Interface implemented by all device drivers.
A mini-server for network communication.
A base class for nested structures that can be searched.