|
| RemoteControlBoardRemapper ()=default |
|
| RemoteControlBoardRemapper (const RemoteControlBoardRemapper &)=delete |
|
| RemoteControlBoardRemapper (RemoteControlBoardRemapper &&)=delete |
|
RemoteControlBoardRemapper & | operator= (const RemoteControlBoardRemapper &)=delete |
|
RemoteControlBoardRemapper & | operator= (RemoteControlBoardRemapper &&)=delete |
|
| ~RemoteControlBoardRemapper () override=default |
|
bool | open (yarp::os::Searchable &prop) override |
| Open the device driver.
|
|
bool | close () override |
| Close the device driver by deallocating all resources and closing ports.
|
|
| ControlBoardRemapper ()=default |
|
| ControlBoardRemapper (const ControlBoardRemapper &)=delete |
|
| ControlBoardRemapper (ControlBoardRemapper &&)=delete |
|
ControlBoardRemapper & | operator= (const ControlBoardRemapper &)=delete |
|
ControlBoardRemapper & | operator= (ControlBoardRemapper &&)=delete |
|
| ~ControlBoardRemapper () override=default |
|
bool | verbose () const |
| Return the value of the verbose flag.
|
|
bool | detachAll () override |
| Detach the object (you must have first called attach).
|
|
bool | attachAll (const yarp::dev::PolyDriverList &l) override |
| Attach to a list of objects.
|
|
bool | setPid (const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override |
| ControlBoard methods.
|
|
bool | setPids (const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *ps) override |
| Set new pid value on multiple axes.
|
|
bool | setPidReference (const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override |
| Set the controller reference for a given axis.
|
|
bool | setPidReferences (const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override |
| Set the controller reference, multiple axes.
|
|
bool | setPidErrorLimit (const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override |
| Set the error limit for the controller on a specifi joint.
|
|
bool | setPidErrorLimits (const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override |
| Get the error limit for the controller on all joints.
|
|
bool | getPidError (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override |
| Get the current error for a joint.
|
|
bool | getPidErrors (const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override |
| Get the error of all joints.
|
|
bool | getPidOutput (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override |
| Get the output of the controller (e.g.
|
|
bool | getPidOutputs (const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override |
| Get the output of the controllers (e.g.
|
|
bool | setPidOffset (const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override |
| Set offset value for a given controller.
|
|
bool | getPid (const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *p) override |
| Get current pid value for a specific joint.
|
|
bool | getPids (const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override |
| Get current pid value for a specific joint.
|
|
bool | getPidReference (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override |
| Get the current reference of the pid controller for a specific joint.
|
|
bool | getPidReferences (const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override |
| Get the current reference of all pid controllers.
|
|
bool | getPidErrorLimit (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override |
| Get the error limit for the controller on a specific joint.
|
|
bool | getPidErrorLimits (const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override |
| Get the error limit for all controllers.
|
|
bool | resetPid (const yarp::dev::PidControlTypeEnum &pidtype, int j) override |
| Reset the controller of a given joint, usually sets the current status of the joint as the reference value for the PID, and resets the integrator.
|
|
bool | disablePid (const yarp::dev::PidControlTypeEnum &pidtype, int j) override |
| Disable the pid computation for a joint.
|
|
bool | enablePid (const yarp::dev::PidControlTypeEnum &pidtype, int j) override |
| Enable the pid computation for a joint.
|
|
bool | isPidEnabled (const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override |
| Get the current status (enabled/disabled) of the pid.
|
|
bool | getAxes (int *ax) override |
| Get the number of controlled axes.
|
|
bool | positionMove (int j, double ref) override |
| Set new reference point for a single axis.
|
|
bool | positionMove (const double *refs) override |
| Set new reference point for all axes.
|
|
bool | positionMove (const int n_joints, const int *joints, const double *refs) override |
| Set new reference point for a subset of joints.
|
|
bool | getTargetPosition (const int joint, double *ref) override |
| Get the last position reference for the specified axis.
|
|
bool | getTargetPositions (double *refs) override |
| Get the last position reference for all axes.
|
|
bool | getTargetPositions (const int n_joint, const int *joints, double *refs) override |
| Get the last position reference for the specified group of axes.
|
|
bool | relativeMove (int j, double delta) override |
| Set relative position.
|
|
bool | relativeMove (const double *deltas) override |
| Set relative position, all joints.
|
|
bool | relativeMove (const int n_joints, const int *joints, const double *deltas) override |
| Set relative position for a subset of joints.
|
|
bool | checkMotionDone (int j, bool *flag) override |
| Check if the current trajectory is terminated.
|
|
bool | checkMotionDone (bool *flag) override |
| Check if the current trajectory is terminated.
|
|
bool | checkMotionDone (const int n_joints, const int *joints, bool *flags) override |
| Check if the current trajectory is terminated.
|
|
bool | setRefSpeed (int j, double sp) override |
| Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
|
|
bool | setRefSpeeds (const double *spds) override |
| Set reference speed on all joints.
|
|
bool | setRefSpeeds (const int n_joints, const int *joints, const double *spds) override |
| Set reference speed on all joints.
|
|
bool | setRefAcceleration (int j, double acc) override |
| Set reference acceleration for a joint.
|
|
bool | setRefAccelerations (const double *accs) override |
| Set reference acceleration on all joints.
|
|
bool | setRefAccelerations (const int n_joints, const int *joints, const double *accs) override |
| Set reference acceleration on all joints.
|
|
bool | getRefSpeed (int j, double *ref) override |
| Get reference speed for a joint.
|
|
bool | getRefSpeeds (double *spds) override |
| Get reference speed of all joints.
|
|
bool | getRefSpeeds (const int n_joints, const int *joints, double *spds) override |
| Get reference speed of all joints.
|
|
bool | getRefAcceleration (int j, double *acc) override |
| Get reference acceleration for a joint.
|
|
bool | getRefAccelerations (double *accs) override |
| Get reference acceleration of all joints.
|
|
bool | getRefAccelerations (const int n_joints, const int *joints, double *accs) override |
| Get reference acceleration for a joint.
|
|
bool | stop (int j) override |
| Stop motion, single joint.
|
|
bool | stop () override |
| Stop motion, multiple joints.
|
|
bool | stop (const int n_joints, const int *joints) override |
| Stop motion for subset of joints.
|
|
bool | getLastJointFault (int j, int &fault, std::string &message) override |
|
bool | velocityMove (int j, double v) override |
| Start motion at a given speed, single joint.
|
|
bool | velocityMove (const double *v) override |
| Start motion at a given speed, multiple joints.
|
|
bool | resetEncoder (int j) override |
| Reset encoder, single joint.
|
|
bool | resetEncoders () override |
| Reset encoders.
|
|
bool | setEncoder (int j, double val) override |
| Set the value of the encoder for a given joint.
|
|
bool | setEncoders (const double *vals) override |
| Set the value of all encoders.
|
|
bool | getEncoder (int j, double *v) override |
| Read the value of an encoder.
|
|
bool | getEncoders (double *encs) override |
| Read the position of all axes.
|
|
bool | getEncodersTimed (double *encs, double *t) override |
| Read the instantaneous acceleration of all axes.
|
|
bool | getEncoderTimed (int j, double *v, double *t) override |
| Read the instantaneous acceleration of all axes.
|
|
bool | getEncoderSpeed (int j, double *sp) override |
| Read the istantaneous speed of an axis.
|
|
bool | getEncoderSpeeds (double *spds) override |
| Read the instantaneous speed of all axes.
|
|
bool | getEncoderAcceleration (int j, double *acc) override |
| Read the instantaneous acceleration of an axis.
|
|
bool | getEncoderAccelerations (double *accs) override |
| Read the instantaneous acceleration of all axes.
|
|
bool | getNumberOfMotorEncoders (int *num) override |
| Get the number of available motor encoders.
|
|
bool | resetMotorEncoder (int m) override |
| Reset motor encoder, single motor.
|
|
bool | resetMotorEncoders () override |
| Reset motor encoders.
|
|
bool | setMotorEncoderCountsPerRevolution (int m, const double cpr) override |
| Sets number of counts per revolution for motor encoder m.
|
|
bool | getMotorEncoderCountsPerRevolution (int m, double *cpr) override |
| Gets number of counts per revolution for motor encoder m.
|
|
bool | setMotorEncoder (int m, const double val) override |
| Set the value of the motor encoder for a given motor.
|
|
bool | setMotorEncoders (const double *vals) override |
| Set the value of all motor encoders.
|
|
bool | getMotorEncoder (int m, double *v) override |
| Read the value of a motor encoder.
|
|
bool | getMotorEncoders (double *encs) override |
| Read the position of all motor encoders.
|
|
bool | getMotorEncodersTimed (double *encs, double *t) override |
| Read the instantaneous position of all motor encoders.
|
|
bool | getMotorEncoderTimed (int m, double *v, double *t) override |
| Read the instantaneous position of a motor encoder.
|
|
bool | getMotorEncoderSpeed (int m, double *sp) override |
| Read the istantaneous speed of a motor encoder.
|
|
bool | getMotorEncoderSpeeds (double *spds) override |
| Read the instantaneous speed of all motor encoders.
|
|
bool | getMotorEncoderAcceleration (int m, double *acc) override |
| Read the instantaneous acceleration of a motor encoder.
|
|
bool | getMotorEncoderAccelerations (double *accs) override |
| Read the instantaneous acceleration of all motor encoders.
|
|
bool | enableAmp (int j) override |
| Enable the amplifier on a specific joint.
|
|
bool | disableAmp (int j) override |
| Disable the amplifier on a specific joint.
|
|
bool | getAmpStatus (int *st) override |
|
bool | getAmpStatus (int j, int *v) override |
|
bool | setMaxCurrent (int j, double v) override |
|
bool | getMaxCurrent (int j, double *v) override |
| Returns the maximum electric current allowed for a given motor.
|
|
bool | getNominalCurrent (int m, double *val) override |
|
bool | setNominalCurrent (int m, const double val) override |
|
bool | getPeakCurrent (int m, double *val) override |
|
bool | setPeakCurrent (int m, const double val) override |
|
bool | getPWM (int m, double *val) override |
|
bool | getPWMLimit (int m, double *val) override |
|
bool | setPWMLimit (int m, const double val) override |
|
bool | getPowerSupplyVoltage (int m, double *val) override |
|
bool | setLimits (int j, double min, double max) override |
| Set the software limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation.
|
|
bool | getLimits (int j, double *min, double *max) override |
| Get the software limits for a particular axis.
|
|
bool | setVelLimits (int j, double min, double max) override |
| Set the software speed limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation.
|
|
bool | getVelLimits (int j, double *min, double *max) override |
| Get the software speed limits for a particular axis.
|
|
bool | getRemoteVariable (std::string key, yarp::os::Bottle &val) override |
|
bool | setRemoteVariable (std::string key, const yarp::os::Bottle &val) override |
|
bool | getRemoteVariablesList (yarp::os::Bottle *listOfKeys) override |
|
bool | isCalibratorDevicePresent (bool *isCalib) override |
| isCalibratorDevicePresent: check if a calibrator device has been set
|
|
yarp::dev::IRemoteCalibrator * | getCalibratorDevice () override |
| getCalibratorDevice: return the pointer stored with the setCalibratorDevice
|
|
bool | calibrateSingleJoint (int j) override |
| calibrateSingleJoint: call the calibration procedure for the single joint
|
|
bool | calibrateWholePart () override |
| calibrateWholePart: call the procedure for calibrating the whole device
|
|
bool | homingSingleJoint (int j) override |
| homingSingleJoint: call the homing procedure for a single joint
|
|
bool | homingWholePart () override |
| homingWholePart: call the homing procedure for a the whole part/device
|
|
bool | parkSingleJoint (int j, bool _wait=true) override |
| parkSingleJoint(): start the parking procedure for the single joint
|
|
bool | parkWholePart () override |
| parkWholePart: start the parking procedure for the whole part
|
|
bool | quitCalibrate () override |
| quitCalibrate: interrupt the calibration procedure
|
|
bool | quitPark () override |
| quitPark: interrupt the park procedure
|
|
bool | calibrateAxisWithParams (int j, unsigned int ui, double v1, double v2, double v3) override |
| Start calibration, this method is very often platform specific.
|
|
bool | setCalibrationParameters (int j, const yarp::dev::CalibrationParameters ¶ms) override |
| Start calibration, this method is very often platform specific.
|
|
bool | calibrationDone (int j) override |
| Check if the calibration is terminated, on a particular joint.
|
|
bool | abortPark () override |
|
bool | abortCalibration () override |
|
bool | getNumberOfMotors (int *num) override |
| Retrieves the number of controlled motors from the current physical interface.
|
|
bool | getTemperature (int m, double *val) override |
| Get temperature of a motor.
|
|
bool | getTemperatures (double *vals) override |
| Get temperature of all the motors.
|
|
bool | getTemperatureLimit (int m, double *val) override |
| Retreives the current temperature limit for a specific motor.
|
|
bool | setTemperatureLimit (int m, const double val) override |
| Set the temperature limit for a specific motor.
|
|
bool | getGearboxRatio (int m, double *val) override |
| Get the gearbox ratio for a specific motor.
|
|
bool | setGearboxRatio (int m, const double val) override |
| Set the gearbox ratio for a specific motor.
|
|
bool | getAxisName (int j, std::string &name) override |
|
bool | getJointType (int j, yarp::dev::JointTypeEnum &type) override |
|
bool | getRefTorques (double *refs) override |
| Get the reference value of the torque for all joints.
|
|
bool | getRefTorque (int j, double *t) override |
| Get the reference value of the torque for a given joint.
|
|
bool | setRefTorques (const double *t) override |
| Set the reference value of the torque for all joints.
|
|
bool | setRefTorque (int j, double t) override |
| Set the reference value of the torque for a given joint.
|
|
bool | setRefTorques (const int n_joint, const int *joints, const double *t) override |
| Set new torque reference for a subset of joints.
|
|
bool | getMotorTorqueParams (int j, yarp::dev::MotorTorqueParameters *params) override |
| Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
|
|
bool | setMotorTorqueParams (int j, const yarp::dev::MotorTorqueParameters params) override |
| Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
|
|
bool | setImpedance (int j, double stiff, double damp) override |
| Set current impedance gains (stiffness,damping) for a specific joint.
|
|
bool | setImpedanceOffset (int j, double offset) override |
| Set current force Offset for a specific joint.
|
|
bool | getTorque (int j, double *t) override |
| Get the value of the torque on a given joint (this is the feedback if you have a torque sensor).
|
|
bool | getTorques (double *t) override |
| Get the value of the torque for all joints (this is the feedback if you have torque sensors).
|
|
bool | getTorqueRange (int j, double *min, double *max) override |
| Get the full scale of the torque sensor of a given joint.
|
|
bool | getTorqueRanges (double *min, double *max) override |
| Get the full scale of the torque sensors of all joints.
|
|
bool | getImpedance (int j, double *stiff, double *damp) override |
| Get current impedance gains (stiffness,damping,offset) for a specific joint.
|
|
bool | getImpedanceOffset (int j, double *offset) override |
| Get current force Offset for a specific joint.
|
|
bool | getCurrentImpedanceLimit (int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override |
| Get the current impedandance limits for a specific joint.
|
|
bool | getControlMode (int j, int *mode) override |
| Get the current control mode.
|
|
bool | getControlModes (int *modes) override |
| Get the current control mode (multiple joints).
|
|
bool | getControlModes (const int n_joint, const int *joints, int *modes) override |
| Get the current control mode for a subset of axes.
|
|
bool | setControlMode (const int j, const int mode) override |
| Set the current control mode.
|
|
bool | setControlModes (const int n_joints, const int *joints, int *modes) override |
| Set the current control mode for a subset of axes.
|
|
bool | setControlModes (int *modes) override |
| Set the current control mode (multiple joints).
|
|
bool | setPosition (int j, double ref) override |
| Set new position for a single axis.
|
|
bool | setPositions (const int n_joints, const int *joints, const double *dpos) override |
| Set new reference point for all axes.
|
|
bool | setPositions (const double *refs) override |
| Set new position for a set of axis.
|
|
bool | getRefPosition (const int joint, double *ref) override |
| Get the last position reference for the specified axis.
|
|
bool | getRefPositions (double *refs) override |
| Get the last position reference for all axes.
|
|
bool | getRefPositions (const int n_joint, const int *joints, double *refs) override |
| Get the last position reference for the specified group of axes.
|
|
yarp::os::Stamp | getLastInputStamp () override |
| Return the time stamp relative to the last acquisition.
|
|
bool | velocityMove (const int n_joints, const int *joints, const double *spds) override |
| Start motion at a given speed for a subset of joints.
|
|
bool | getRefVelocity (const int joint, double *vel) override |
| Get the last reference speed set by velocityMove for single joint.
|
|
bool | getRefVelocities (double *vels) override |
| Get the last reference speed set by velocityMove for all joints.
|
|
bool | getRefVelocities (const int n_joint, const int *joints, double *vels) override |
| Get the last reference speed set by velocityMove for a group of joints.
|
|
bool | getInteractionMode (int j, yarp::dev::InteractionModeEnum *mode) override |
| Get the current interaction mode of the robot, values can be stiff or compliant.
|
|
bool | getInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override |
| Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
|
|
bool | getInteractionModes (yarp::dev::InteractionModeEnum *modes) override |
| Get the current interaction mode of the robot for a all the joints, values can be stiff or compliant.
|
|
bool | setInteractionMode (int j, yarp::dev::InteractionModeEnum mode) override |
| Set the interaction mode of the robot, values can be stiff or compliant.
|
|
bool | setInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override |
| Set the interaction mode of the robot for a set of joints, values can be stiff or compliant.
|
|
bool | setInteractionModes (yarp::dev::InteractionModeEnum *modes) override |
| Set the interaction mode of the robot for a all the joints, values can be stiff or compliant.
|
|
bool | setRefDutyCycle (int m, double ref) override |
| Sets the reference dutycycle to a single motor.
|
|
bool | setRefDutyCycles (const double *refs) override |
| Sets the reference dutycycle for all the motors.
|
|
bool | getRefDutyCycle (int m, double *ref) override |
| Gets the last reference sent using the setRefDutyCycle function.
|
|
bool | getRefDutyCycles (double *refs) override |
| Gets the last reference sent using the setRefDutyCycles function.
|
|
bool | getDutyCycle (int m, double *val) override |
| Gets the current dutycycle of the output of the amplifier (i.e.
|
|
bool | getDutyCycles (double *vals) override |
| Gets the current dutycycle of the output of the amplifier (i.e.
|
|
bool | getCurrent (int m, double *curr) override |
| Get the instantaneous current measurement for a single motor.
|
|
bool | getCurrents (double *currs) override |
| Get the instantaneous current measurement for all motors.
|
|
bool | getCurrentRange (int m, double *min, double *max) override |
| Get the full scale of the current measurement for a given motor (e.g.
|
|
bool | getCurrentRanges (double *min, double *max) override |
| Get the full scale of the current measurements for all motors motor (e.g.
|
|
bool | setRefCurrents (const double *currs) override |
| Set the reference value of the currents for all motors.
|
|
bool | setRefCurrent (int m, double curr) override |
| Set the reference value of the current for a single motor.
|
|
bool | setRefCurrents (const int n_motor, const int *motors, const double *currs) override |
| Set the reference value of the current for a group of motors.
|
|
bool | getRefCurrents (double *currs) override |
| Get the reference value of the currents for all motors.
|
|
bool | getRefCurrent (int m, double *curr) override |
| Get the reference value of the current for a single motor.
|
|
| DeviceDriver () |
|
| DeviceDriver (const DeviceDriver &other)=delete |
|
| DeviceDriver (DeviceDriver &&other) noexcept=delete |
|
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
|
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
|
virtual | ~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 DeviceDriver * | getImplementation () |
| Some drivers are bureaucrats, pointing at others.
|
|
virtual | ~IPidControl () |
| Destructor.
|
|
virtual | ~IPositionControl () |
| Destructor.
|
|
virtual | ~IPositionDirect () |
| Destructor.
|
|
virtual | ~IVelocityControl () |
| Destructor.
|
|
virtual | ~IPWMControl () |
|
virtual | ~ICurrentControl () |
| Destructor.
|
|
virtual | ~IEncodersTimed () |
| Destructor.
|
|
virtual | ~IEncoders () |
| Destructor.
|
|
virtual | ~IMotor () |
| Destructor.
|
|
virtual | ~IMotorEncoders () |
| Destructor.
|
|
virtual | ~IAmplifierControl () |
| Destructor.
|
|
virtual | ~IControlLimits () |
| Destructor.
|
|
| IRemoteCalibrator () |
| This interface is meant to remotize the access of the calibration device in order to allow users to remotely call the calibration procedure for a single joint or the whole device and let the calibrator do the job.
|
|
virtual | ~IRemoteCalibrator ()=default |
|
virtual bool | setCalibratorDevice (yarp::dev::IRemoteCalibrator *dev) |
| setCalibratorDevice: store the pointer to the calibrator device.
|
|
virtual void | releaseCalibratorDevice () |
| releaseCalibratorDevice: reset the internal pointer to NULL when stop using the calibrator
|
|
| IControlCalibration () |
|
virtual | ~IControlCalibration () |
| Destructor.
|
|
virtual bool | setCalibrator (ICalibrator *c) |
| Set the calibrator object to be used to calibrate the robot.
|
|
virtual bool | calibrateRobot () |
| Calibrate robot by using an external calibrator.
|
|
virtual bool | park (bool wait=true) |
|
virtual | ~ITorqueControl () |
| Destructor.
|
|
virtual | ~IImpedanceControl () |
| Destructor.
|
|
virtual | ~IControlMode () |
|
virtual | ~IMultipleWrapper () |
| Destructor.
|
|
virtual | ~IAxisInfo () |
| Destructor.
|
|
virtual | ~IPreciselyTimed () |
|
virtual | ~IInteractionMode () |
| Destructor.
|
|
virtual | ~IRemoteVariables () |
| Destructor.
|
|
virtual | ~IJointFault () |
|
remotecontrolboardremapper
A device that takes a list of axes from multiple controlboards, a list of remote controlboards in which this axes are located, that is opening all the remote controlboards but is exposing them
RemoteControlBoardRemapper
Parameters required by this device are:
Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
axesNames | - | vector of strings | - | - | Yes | Ordered list of the axes that are part of the remapped device. | |
remoteControlBoards | - | vector of strings | - | - | Yes | List of remote prefix used by the remote controlboards. | The element of this list are then passed as "remote" parameter to the RemoteControlBoard device. |
localPortPrefix | - | string | - | - | Yes | All ports opened by this device will start with this prefix | |
REMOTE_CONTROLBOARD_OPTIONS | - | group | - | - | No | Options that will be passed directly to the remote_controlboard devices | |
All the passed remote controlboards are opened, and then the axesNames and the opened device are passed to the ControlBoardRemapper device. If different axes in two attached controlboard have the same name, the behaviour of this device is undefined.
Configuration file using .ini format.
device remotecontrolboardremapper
axesNames (torso_pitch torso_roll torso_yaw neck_pitch neck_roll neck_yaw)
remoteControlBoards (/icub/torso /icub/head)
[REMOTE_CONTROLBOARD_OPTIONS]
writeStrict on
...
Configuration of the device from C++ code.
Property options;
options.put("device","remotecontrolboardremapper");
Bottle axesNames;
Bottle & axesList = axesNames.addList();
axesList.addString("torso_pitch");
axesList.addString("torso_roll");
axesList.addString("torso_yaw");
axesList.addString("neck_pitch");
axesList.addString("neck_roll");
axesList.addString("neck_yaw");
options.put("axesNames",axesNames.get(0))
Bottle remoteControlBoards;
Bottle & remoteControlBoardsList = remoteControlBoards.addList();
remoteControlBoardsList.addString("/icub/torso");
remoteControlBoardsList.addString("/icub/head");
options.put("remoteControlBoards",remoteControlBoards.get(0));
options.put("localPortPrefix",/test");
Property & remoteControlBoardsOpts = options.addGroup("REMOTE_CONTROLBOARD_OPTIONS");
remoteControlBoardsOpts.put("writeStrict","on");
// Actually open the device
PolyDriver robotDevice(options);
// Use it as you would use any controlboard device
// ...
Caveat
By design, the RemoteControlBoardRemapper is more limited with respect to a true RemoteControlBoard. Known limitations include:
- If some axes belong to a coupled mechanics, all the axes should be added to the RemoteControlBoardRemapper. If only an axis of a coupled mechanics is added to the remapper, the semantic of the coupled mechanics in the underlyng implementation could create confusing behaviour. For example, changing the control mode of an axis in a coupled mechanism could change the control mode of the other coupled axes, even if the other coupled axes are not part of the remapped controlboard.
- The debug methods provided by IRemoteVariables are not supported by the RemoteControlBoardRemapper .
Definition at line 94 of file RemoteControlBoardRemapper.h.