MobileBaseVelocityControl_nws_ros
: A device which allows a client application to control the velocity of a mobile base from ROS. The device opens a topic of type yarp::rosmsg::geometry_msgs::Twist
to receive user commands
More...
Public Member Functions | |
virtual | ~MobileBaseVelocityControl_nws_ros () |
MobileBaseVelocityControl_nws_ros () | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. | |
bool | close () override |
Close the DeviceDriver. | |
Public Member Functions inherited from yarp::dev::DeviceDriver | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
~DeviceDriver () override | |
virtual std::string | id () const |
Return the id assigned to the PolyDriver. | |
virtual void | setId (const std::string &id) |
Set the id for this device. | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. | |
Public Member Functions inherited from yarp::os::IConfig | |
virtual | ~IConfig () |
Destructor. | |
virtual bool | configure (Searchable &config) |
Change online parameters. | |
Public Member Functions inherited from yarp::dev::WrapperSingle | |
~WrapperSingle () override | |
Destructor. | |
bool | attachAll (const yarp::dev::PolyDriverList &drivers) final |
Attach to a list of objects. | |
bool | detachAll () final |
Detach the object (you must have first called attach). | |
Public Member Functions inherited from yarp::dev::IWrapper | |
virtual | ~IWrapper () |
Destructor. | |
Public Member Functions inherited from yarp::dev::IMultipleWrapper | |
virtual | ~IMultipleWrapper () |
Destructor. | |
Protected Attributes | |
std::string | m_ros_node_name = "/mobileBase_VelControl_nws_ros" |
std::string | m_ros_topic_name = "/velocity_input" |
yarp::os::Node * | m_ros_node = nullptr |
commandSubscriber * | m_command_subscriber = nullptr |
yarp::dev::PolyDriver | m_subdev |
MobileBaseVelocityControl_nws_ros
: A device which allows a client application to control the velocity of a mobile base from ROS. The device opens a topic of type yarp::rosmsg::geometry_msgs::Twist
to receive user commands
Parameters required by this device are:
Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
---|---|---|---|---|---|---|---|
node_name | - | string | - | /mobileBase_VelControl_nws_ros | No | Full name of the opened ROS node | |
topic_name | - | string | - | /velocity_input | No | Full name of the opened ROS topic |
Definition at line 54 of file MobileBaseVelocityControl_nws_ros.h.
|
inlinevirtual |
Definition at line 67 of file MobileBaseVelocityControl_nws_ros.h.
|
inline |
Definition at line 68 of file MobileBaseVelocityControl_nws_ros.h.
|
overridevirtual |
Close the DeviceDriver.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 92 of file MobileBaseVelocityControl_nws_ros.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device). |
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 62 of file MobileBaseVelocityControl_nws_ros.cpp.
|
protected |
Definition at line 62 of file MobileBaseVelocityControl_nws_ros.h.
|
protected |
Definition at line 61 of file MobileBaseVelocityControl_nws_ros.h.
|
protected |
Definition at line 59 of file MobileBaseVelocityControl_nws_ros.h.
|
protected |
Definition at line 60 of file MobileBaseVelocityControl_nws_ros.h.
|
protected |
Definition at line 64 of file MobileBaseVelocityControl_nws_ros.h.