|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
9 #ifndef YARP_DEV_JOYPADCONTROLSERVER_JOYPADCONTROLSERVER_H
10 #define YARP_DEV_JOYPADCONTROLSERVER_JOYPADCONTROLSERVER_H
31 std::map<int, getcountmethod> countGetters;
64 bool m_isSubdeviceOwned;
67 std::string m_rpcPortName;
93 bool close()
override;
JoypadCtrl_coordinateMode
A simple collection of objects that can be described and transmitted in a portable way.
A base class for nested structures that can be searched.
JoypadControlServer: Documentation to be added
bool detachAll() override
Detach the object (you must have first called attach).
Interface implemented by all device drivers.
bool detach() override
Detach the object (you must have first called attach).
~JoypadControlServer() override
bool attachAll(const yarp::dev::PolyDriverList &p) override
Attach to a list of objects.
JoypadControlServer & operator=(const JoypadControlServer &)=delete
A mini-server for network communication.
A container for a device driver.
bool respond(const yarp::os::Bottle &cmd, yarp::os::Bottle &response) override
Respond to a message.
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
Interface for an object that can wrap/or "attach" to another.
An abstraction for a periodic thread.
bool fromConfig(yarp::os::Searchable ¶ms)
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
A cheap and cheerful framework for human readable/writable forms of messages to devices.
void run() override
Loop function.
Interface for an object that can wrap/attach to to another.
JoypadControlServer & operator=(JoypadControlServer &&)=delete
JoypadControlServer(const JoypadControlServer &)=delete
bool configure(yarp::dev::IJoypadController *interface)
JoypadControlServer(JoypadControlServer &&)=delete
bool threadInit() override
Initialization method.
~JoypadCtrlParser() override=default