YARP
Yet Another Robot Platform
yarp::os::IConfig Class Reference

An object that can be configured. More...

#include <yarp/os/IConfig.h>

+ Inheritance diagram for yarp::os::IConfig:

Public Member Functions

virtual ~IConfig ()
 Destructor. More...
 
virtual bool open (Searchable &config)
 Initialize the object. More...
 
virtual bool close ()
 Shut the object down. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 

Detailed Description

An object that can be configured.

When possible, we separate out the configuration for modules and devices into external files, command line options, or GUIs.

Definition at line 26 of file IConfig.h.

Constructor & Destructor Documentation

◆ ~IConfig()

yarp::os::IConfig::~IConfig ( )
virtualdefault

Destructor.

Member Function Documentation

◆ close()

bool yarp::os::IConfig::close ( )
virtual

Shut the object down.

You should override this.

Returns
true/false on success/failure.

Reimplemented in yarp::dev::PolyDriver, StubDriver, yarp::dev::DeviceDriver, VirtualAnalogWrapper, V4L_camera, USBCameraDriver, UpowerBattery, FrameTransformServer, FrameTransformClient, SegFault, Nop, ServerSoundGrabber, ServerSerial, ServerInertial, ServerGrabber, ServerFrameGrabber, SerialServoBoard, SerialDeviceDriver, SDLJoypad, RpLidar2, RpLidar, RobotDescriptionServer, RobotDescriptionClient, RGBDSensorWrapper, RGBDSensorFromRosTopic, RGBDSensorClient, RemoteFrameGrabber, RemoteControlBoard, Rangefinder2DWrapper, Rangefinder2DClient, PortAudioRecorderDeviceDriver, PortAudioPlayerDeviceDriver, PortAudioDeviceDriver, OpenCVGrabber, navigation2DServer, Navigation2DClient, MultipleAnalogSensorsServer, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, MultipleAnalogSensorsRemapper, MultipleAnalogSensorsClient, Map2DServer, Map2DClient, Localization2DServer, Localization2DClient, laserHokuyo, LaserFromRosTopic, LaserFromPointCloud, LaserFromExternalPort, LaserFromDepth, JoypadControlServer, JoypadControlClient, BoschIMU, FfmpegWriter, FfmpegGrabber, fakeSpeaker, fakeNavigation, FakeMotor, FakeMotionControl, fakeMicrophone, fakeLocalizer, FakeLaser, fakeIMU, FakeFrameGrabber, fakeDepthCameraDriver, FakeBot, FakeBattery, FakeAnalogSensor, DynamixelAX12FtdiDriver, DevicePipe, DeviceGroup, depthCameraDriver, ControlBoardWrapper, RemoteControlBoardRemapper, ControlBoardRemapper, BatteryWrapper, BatteryClient, audioToFileDevice, AudioRecorderWrapper, AudioPlayerWrapper, audioFromFileDevice, AnalogWrapper, AnalogSensorClient, and yarp::dev::OVRHeadset.

Definition at line 21 of file IConfig.cpp.

◆ configure()

bool yarp::os::IConfig::configure ( Searchable config)
virtual

Change online parameters.

The parameters that can be changed online (in other words, without closing and reopening) will vary between objects.

Parameters
configA list of parameters for the object.
Returns
true/false on success/failure.

Reimplemented in DynamixelAX12FtdiDriver.

Definition at line 26 of file IConfig.cpp.

◆ open()

bool yarp::os::IConfig::open ( Searchable config)
virtual

Initialize the object.

You should override this.

Parameters
configis a list of parameters for the object. Which parameters are effective for your object can vary.
Returns
true/false upon success/failure

Reimplemented in navigation2DServer, Localization2DServer, ControlBoardWrapper, RemoteControlBoardRemapper, ControlBoardRemapper, FrameTransformServer, RGBDSensorWrapper, Rangefinder2DWrapper, MultipleAnalogSensorsServer, GenericSensorRosPublisher< ROS_MSG >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Temperature >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::WrenchStamped >, GenericSensorRosPublisher< yarp::rosmsg::geometry_msgs::PoseStamped >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::MagneticField >, GenericSensorRosPublisher< yarp::rosmsg::sensor_msgs::Imu >, Map2DServer, JoypadControlServer, BatteryWrapper, AudioPlayerWrapper, AnalogWrapper, FakeMotionControl, yarp::dev::PolyDriver, StubDriver, yarp::dev::DeviceDriver, VirtualAnalogWrapper, V4L_camera, USBCameraDriver, UpowerBattery, FrameTransformClient, SegFault, Nop, ServerSoundGrabber, ServerInertial, ServerGrabber, ServerFrameGrabber, SerialDeviceDriver, SDLJoypad, RpLidar2, RpLidar, RobotDescriptionServer, RobotDescriptionClient, RGBDSensorFromRosTopic, RGBDSensorClient, RemoteFrameGrabber, Rangefinder2DClient, PortAudioRecorderDeviceDriver, PortAudioPlayerDeviceDriver, PortAudioDeviceDriver, OpenCVGrabber, Navigation2DClient, MultipleAnalogSensorsRemapper, MultipleAnalogSensorsClient, Map2DClient, Localization2DClient, laserHokuyo, LaserFromRosTopic, LaserFromPointCloud, LaserFromExternalPort, LaserFromDepth, JoypadControlClient, BoschIMU, FfmpegWriter, FfmpegGrabber, fakeSpeaker, fakeNavigation, TestMotor, FakeMotor, fakeMicrophone, fakeLocalizer, FakeLaser, fakeIMU, TestFrameGrabber, FakeFrameGrabber, fakeDepthCameraDriver, FakeBot, FakeBattery, FakeAnalogSensor, DynamixelAX12FtdiDriver, DevicePipe, DeviceGroup, depthCameraDriver, BatteryClient, audioToFileDevice, AudioRecorderWrapper, audioFromFileDevice, AnalogSensorClient, yarp::dev::OVRHeadset, ServerSerial, SerialServoBoard, and RemoteControlBoard.

Definition at line 15 of file IConfig.cpp.


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