YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
yarp::dev::DeviceDriver Class Reference

Interface implemented by all device drivers. More...

#include <yarp/dev/DeviceDriver.h>

Inherits yarp::os::IConfig.

Inherited by GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >, GenericSensor_nws_ros2< sensor_msgs::msg::Imu >, GenericSensor_nws_ros2< geometry_msgs::msg::WrenchStamped >, AnalogSensorClient, AnalogWrapper, AudioPlayerWrapper, AudioRecorderWrapper, AudioRecorder_nwc_yarp, AudioRecorder_nws_yarp, Battery_nwc_yarp, Battery_nws_ros2, Battery_nws_yarp, BoschIMU, ChatBot_nwc_yarp, ChatBot_nws_yarp, ControlBoardRemapper, ControlBoard_nws_ros, ControlBoard_nws_ros2, ControlBoard_nws_yarp, DeviceTemplate, DynamixelAX12FtdiDriver, FakeAnalogSensor, FakeBattery, FakeChatBotDevice, FakeFrameGrabber [virtual], FakeJointCoupling, FakeJoypad, FakeLaser, FakeLaserWithMotor, FakeMotionControl, FakeMotionControlMicro, FakeOdometry2D, FakePositionSensor, FakeSerialPort, FakeSpeechSynthesizer, FakeSpeechTranscription, FfmpegGrabber, FfmpegWriter, FrameGrabberCropper, FrameGrabber_nwc_yarp, FrameGrabber_nws_ros, FrameGrabber_nws_ros2, FrameGrabber_nws_yarp, FrameTransformClient, FrameTransformGetMultiplexer, FrameTransformGet_nwc_ros, FrameTransformGet_nwc_ros2, FrameTransformGet_nwc_yarp, FrameTransformGet_nws_yarp, FrameTransformServer, FrameTransformSetMultiplexer, FrameTransformSet_nwc_ros, FrameTransformSet_nwc_ros2, FrameTransformSet_nwc_yarp, FrameTransformSet_nws_yarp, FrameTransformStorage, GPTDevice, GenericSensorRosPublisher< ROS_MSG >, GenericSensor_nwc_ros2< ROS_MSG >, GenericSensor_nws_ros2< ROS_MSG >, JoypadControlClient, JoypadControlServer, LLM_nwc_yarp, LLM_nws_yarp, LaserFromDepth, LaserFromExternalPort, LaserFromPointCloud, LaserFromRosTopic, Localization2D_nwc_yarp, Localization2D_nws_ros, Localization2D_nws_ros2, Localization2D_nws_yarp, Map2DStorage, Map2D_nwc_yarp, Map2D_nws_ros, Map2D_nws_ros2, Map2D_nws_yarp, MobileBaseVelocityControl_nwc_yarp, MobileBaseVelocityControl_nws_ros, MobileBaseVelocityControl_nws_ros2, MobileBaseVelocityControl_nws_yarp, MultipleAnalogSensorsClient, MultipleAnalogSensorsRemapper, MultipleAnalogSensorsServer, Navigation2D_nwc_yarp, Nop, Odometry2D_nws_ros, Odometry2D_nws_ros2, Odometry2D_nws_yarp, OpenCVGrabber, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, RGBDSensorClient, RGBDSensorFromRosTopic, RGBDToPointCloudSensor_nws_ros, Rangefinder2DClient, Rangefinder2D_controlBoard_nws_ros2, Rangefinder2D_nwc_ros2, Rangefinder2D_nwc_yarp, Rangefinder2D_nws_ros, Rangefinder2D_nws_ros2, Rangefinder2D_nws_yarp, RemoteControlBoard, RgbdSensor_nwc_ros2, RgbdSensor_nws_ros, RgbdSensor_nws_ros2, RgbdSensor_nws_yarp, RgbdToPointCloudSensor_nws_ros2, RobotDescriptionClient, RobotDescriptionServer, Ros2Test, RpLidar, RpLidar2, RpLidar3, RpLidar4, SDLJoypad, SegFault, SerialDeviceDriver, SerialPort_nwc_yarp, SerialPort_nws_yarp, SerialServoBoard, SpeechSynthesizer_nwc_yarp, SpeechSynthesizer_nws_yarp, SpeechTranscription_nwc_yarp, SpeechTranscription_nws_yarp, StubDriver, USBCameraDriver, UltraPythonDriver, UpowerBattery, V4L_camera, VirtualAnalogWrapper, WhisperSpeechTranscription, audioFromFileDevice, audioToFileDevice, depthCameraDriver, fakeDepthCameraDriver, fakeIMU, fakeLLMDevice, fakeLocalizer, fakeMicrophone, fakeNavigation, fakeSpeaker, laserHokuyo, navigation2D_nws_yarp, pylonCameraDriver, realsense2Driver, realsense2Tracking, yarp::dev::DeprecatedDeviceDriver [virtual], yarp::dev::OVRHeadset, and yarp::dev::PolyDriver.

Classes

class  Private
 

Public Member Functions

 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (DeviceDriver &&other) noexcept=delete
 
 ~DeviceDriver () override
 
bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
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 DeviceDrivergetImplementation ()
 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.
 

Detailed Description

Interface implemented by all device drivers.

Examples
dev/fake_motor/fake_motor.cpp.

Definition at line 29 of file DeviceDriver.h.

Constructor & Destructor Documentation

◆ DeviceDriver() [1/3]

DeviceDriver::DeviceDriver ( )

Definition at line 28 of file DeviceDriver.cpp.

◆ DeviceDriver() [2/3]

yarp::dev::DeviceDriver::DeviceDriver ( const DeviceDriver other)
delete

◆ DeviceDriver() [3/3]

yarp::dev::DeviceDriver::DeviceDriver ( DeviceDriver &&  other)
deletenoexcept

◆ ~DeviceDriver()

DeviceDriver::~DeviceDriver ( )
override

Definition at line 33 of file DeviceDriver.cpp.

Member Function Documentation

◆ close()

bool yarp::dev::DeviceDriver::close ( )
inlineoverridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::os::IConfig.

Reimplemented in yarp::dev::OVRHeadset, pylonCameraDriver, realsense2Driver, realsense2Tracking, realsense2withIMUDriver, RpLidar, RpLidar2, RpLidar3, RpLidar4, WhisperSpeechTranscription, DeviceTemplate, UltraPythonDriver, GPTDevice, FrameGrabber_nws_ros, FrameTransformGet_nwc_ros, FrameTransformSet_nwc_ros, LaserFromRosTopic, Localization2D_nws_ros, Map2D_nws_ros, MobileBaseVelocityControl_nws_ros, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, Odometry2D_nws_ros, Rangefinder2D_nws_ros, RgbdSensor_nws_ros, RGBDSensorFromRosTopic, RGBDToPointCloudSensor_nws_ros, FrameGrabber_nws_ros2, FrameTransformGet_nwc_ros2, FrameTransformSet_nwc_ros2, Localization2D_nws_ros2, Map2D_nws_ros2, MobileBaseVelocityControl_nws_ros2, GenericSensor_nwc_ros2< ROS_MSG >, GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >, GenericSensor_nws_ros2< ROS_MSG >, GenericSensor_nws_ros2< geometry_msgs::msg::WrenchStamped >, GenericSensor_nws_ros2< sensor_msgs::msg::Imu >, Odometry2D_nws_ros2, Rangefinder2D_controlBoard_nws_ros2, Rangefinder2D_nwc_ros2, Rangefinder2D_nws_ros2, RgbdSensor_nwc_ros2, RgbdSensor_nws_ros2, RgbdToPointCloudSensor_nws_ros2, Ros2Test, RemoteControlBoardRemapper, DynamixelAX12FtdiDriver, FakeAnalogSensor, FakeBattery, FakeBot, fakeDepthCameraDriver, FakeFrameGrabber, fakeIMU, FakeJointCoupling, FakeJoypad, FakeLaser, FakeLaserWithMotor, fakeLocalizer, fakeMicrophone, FakeMotionControl, FakeMotionControlMicro, fakeNavigation, FakeOdometry2D, FakePositionSensor, FakeSerialPort, fakeSpeaker, FakeSpeechSynthesizer, FakeSpeechTranscription, FfmpegGrabber, FfmpegWriter, FrameGrabber_nwc_yarp, FrameGrabber_nws_yarp, FrameGrabberCropper, FrameTransformClient, FrameTransformGet_nwc_yarp, FrameTransformGet_nws_yarp, FrameTransformGetMultiplexer, FrameTransformServer, FrameTransformSet_nwc_yarp, FrameTransformSet_nws_yarp, FrameTransformSetMultiplexer, FrameTransformStorage, JoypadControlClient, JoypadControlServer, LaserFromDepth, LaserFromExternalPort, LaserFromPointCloud, laserHokuyo, LLM_nwc_yarp, LLM_nws_yarp, Localization2D_nwc_yarp, Localization2D_nws_yarp, Map2D_nwc_yarp, Map2D_nws_yarp, Map2DStorage, MobileBaseVelocityControl_nwc_yarp, MobileBaseVelocityControl_nws_yarp, MultipleAnalogSensorsClient, MultipleAnalogSensorsRemapper, MultipleAnalogSensorsServer, Navigation2D_nwc_yarp, navigation2D_nws_yarp, Odometry2D_nws_yarp, OpenCVGrabber, PortAudioDeviceDriver, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, Rangefinder2D_nwc_yarp, Rangefinder2D_nws_yarp, Rangefinder2DClient, RemoteControlBoard, RgbdSensor_nws_yarp, RGBDSensorClient, RobotDescriptionClient, RobotDescriptionServer, SDLJoypad, SerialDeviceDriver, SerialPort_nwc_yarp, SerialPort_nws_yarp, SerialServoBoard, SpeechSynthesizer_nwc_yarp, SpeechSynthesizer_nws_yarp, SpeechTranscription_nwc_yarp, SpeechTranscription_nws_yarp, Nop, SegFault, UpowerBattery, USBCameraDriver, V4L_camera, VirtualAnalogWrapper, StubDriver, and yarp::dev::PolyDriver.

Definition at line 59 of file DeviceDriver.h.

◆ getImplementation()

virtual DeviceDriver * yarp::dev::DeviceDriver::getImplementation ( )
inlinevirtual

Some drivers are bureaucrats, pointing at others.

Such drivers override this method.

Returns
"real" device driver

Reimplemented in StubDriver, and yarp::dev::PolyDriver.

Definition at line 112 of file DeviceDriver.h.

◆ id()

std::string DeviceDriver::id ( ) const
virtual

Return the id assigned to the PolyDriver.

If no name was assigned, returns the name of the device (if set) or an empty string. The value can be set by passing the id option when opening the device or with the setId() method.

Returns
the id for this device.

Reimplemented in StubDriver.

Definition at line 43 of file DeviceDriver.cpp.

◆ open()

bool yarp::dev::DeviceDriver::open ( yarp::os::Searchable config)
inlineoverridevirtual

Open the DeviceDriver.

Parameters
configis 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).
Returns
true/false upon success/failure

Reimplemented from yarp::os::IConfig.

Reimplemented in RemoteControlBoard, SerialServoBoard, SerialPort_nwc_yarp, yarp::dev::OVRHeadset, pylonCameraDriver, realsense2Driver, realsense2Tracking, realsense2withIMUDriver, RpLidar, RpLidar2, RpLidar3, RpLidar4, WhisperSpeechTranscription, DeviceTemplate, UltraPythonDriver, GPTDevice, FrameGrabber_nws_ros, FrameTransformGet_nwc_ros, FrameTransformSet_nwc_ros, LaserFromRosTopic, MobileBaseVelocityControl_nws_ros, RGBDSensorFromRosTopic, FrameGrabber_nws_ros2, FrameTransformGet_nwc_ros2, FrameTransformSet_nwc_ros2, Localization2D_nws_ros2, Map2D_nws_ros2, MobileBaseVelocityControl_nws_ros2, Rangefinder2D_controlBoard_nws_ros2, Rangefinder2D_nwc_ros2, Rangefinder2D_nws_ros2, RgbdSensor_nwc_ros2, RgbdSensor_nws_ros2, RgbdToPointCloudSensor_nws_ros2, Ros2Test, DynamixelAX12FtdiDriver, FakeAnalogSensor, FakeBattery, FakeBot, fakeDepthCameraDriver, FakeFrameGrabber, fakeIMU, FakeJoypad, FakeLaser, FakeLaserWithMotor, fakeLocalizer, fakeMicrophone, fakeNavigation, FakeOdometry2D, FakePositionSensor, FakeSerialPort, fakeSpeaker, FakeSpeechSynthesizer, FakeSpeechTranscription, FfmpegGrabber, FfmpegWriter, FrameGrabber_nwc_yarp, FrameGrabber_nws_yarp, FrameGrabberCropper, FrameTransformClient, FrameTransformGetMultiplexer, FrameTransformServer, FrameTransformSet_nwc_yarp, FrameTransformSet_nws_yarp, FrameTransformSetMultiplexer, FrameTransformStorage, JoypadControlClient, LaserFromDepth, LaserFromExternalPort, LaserFromPointCloud, laserHokuyo, LLM_nwc_yarp, Localization2D_nwc_yarp, Map2D_nwc_yarp, MobileBaseVelocityControl_nwc_yarp, MobileBaseVelocityControl_nws_yarp, MultipleAnalogSensorsClient, MultipleAnalogSensorsRemapper, Navigation2D_nwc_yarp, OpenCVGrabber, PortAudioDeviceDriver, PortAudioPlayerDeviceDriver, PortAudioRecorderDeviceDriver, Rangefinder2D_nwc_yarp, Rangefinder2DClient, RGBDSensorClient, RobotDescriptionClient, RobotDescriptionServer, SDLJoypad, SerialDeviceDriver, SerialPort_nws_yarp, SpeechSynthesizer_nwc_yarp, SpeechSynthesizer_nws_yarp, SpeechTranscription_nwc_yarp, SpeechTranscription_nws_yarp, Nop, SegFault, UpowerBattery, USBCameraDriver, V4L_camera, VirtualAnalogWrapper, StubDriver, yarp::dev::PolyDriver, yarp::dev::PolyDriver, FakeJointCoupling, FakeMotionControl, FakeMotionControlMicro, Map2D_nws_ros, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, Odometry2D_nws_ros, Rangefinder2D_nws_ros, RgbdSensor_nws_ros, RGBDToPointCloudSensor_nws_ros, GenericSensor_nwc_ros2< ROS_MSG >, GenericSensor_nwc_ros2< sensor_msgs::msg::Imu >, GenericSensor_nws_ros2< ROS_MSG >, GenericSensor_nws_ros2< geometry_msgs::msg::WrenchStamped >, GenericSensor_nws_ros2< sensor_msgs::msg::Imu >, Odometry2D_nws_ros2, FrameTransformGet_nwc_yarp, FrameTransformGet_nws_yarp, JoypadControlServer, Map2D_nws_yarp, Map2DStorage, MultipleAnalogSensorsServer, Odometry2D_nws_yarp, Rangefinder2D_nws_yarp, RgbdSensor_nws_yarp, Localization2D_nws_ros, RemoteControlBoardRemapper, LLM_nws_yarp, Localization2D_nws_yarp, and navigation2D_nws_yarp.

Definition at line 53 of file DeviceDriver.h.

◆ operator=() [1/2]

DeviceDriver & yarp::dev::DeviceDriver::operator= ( const DeviceDriver other)
delete

◆ operator=() [2/2]

DeviceDriver & yarp::dev::DeviceDriver::operator= ( DeviceDriver &&  other)
deletenoexcept

◆ setId()

void DeviceDriver::setId ( const std::string &  id)
virtual

Set the id for this device.

Reimplemented in StubDriver.

Definition at line 38 of file DeviceDriver.cpp.

◆ view()

template<class T >
bool yarp::dev::DeviceDriver::view ( T *&  x)
inline

Get an interface to the device driver.

Parameters
xA pointer of type T which will be set to point to this object if that is possible.
Returns
true iff the desired interface is implemented by the device driver.
Examples
dev/grabber_crop/grabber_crop.cpp.

Definition at line 88 of file DeviceDriver.h.


The documentation for this class was generated from the following files: