YARP
Yet Another Robot Platform

controlboardwrapper2: An updated version of the controlBoard network wrapper. More...

#include <ControlBoardWrapper/ControlBoardWrapper.h>

+ Inheritance diagram for ControlBoardWrapper:

Public Member Functions

 ControlBoardWrapper ()
 
 ControlBoardWrapper (const ControlBoardWrapper &)=delete
 
 ControlBoardWrapper (ControlBoardWrapper &&)=delete
 
ControlBoardWrapperoperator= (const ControlBoardWrapper &)=delete
 
ControlBoardWrapperoperator= (ControlBoardWrapper &&)=delete
 
 ~ControlBoardWrapper () override
 
std::string getId ()
 
bool close () override
 Close the device driver by deallocating all resources and closing ports. More...
 
bool open (yarp::os::Searchable &prop) override
 Open the device driver. More...
 
bool detachAll () override
 Detach the object (you must have first called attach). More...
 
bool attachAll (const yarp::dev::PolyDriverList &l) override
 Attach to a list of objects. More...
 
void run () override
 The thread main loop deals with writing on ports here. More...
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 ~DeviceDriver () override=default
 Destructor. More...
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver. More...
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others. More...
 
- Public Member Functions inherited from yarp::os::IConfig
virtual ~IConfig ()
 Destructor. More...
 
virtual bool configure (Searchable &config)
 Change online parameters. More...
 
- Public Member Functions inherited from yarp::os::PeriodicThread
 PeriodicThread (double period, ShouldUseSystemClock useSystemClock=ShouldUseSystemClock::No)
 Constructor. More...
 
virtual ~PeriodicThread ()
 
bool start ()
 Call this to start the thread. More...
 
void step ()
 Call this to "step" the thread rather than starting it. More...
 
void stop ()
 Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() called). More...
 
void askToStop ()
 Stop the thread. More...
 
bool isRunning () const
 Returns true when the thread is started, false otherwise. More...
 
bool isSuspended () const
 Returns true when the thread is suspended, false otherwise. More...
 
bool setPeriod (double period)
 Set the (new) period of the thread. More...
 
double getPeriod () const
 Return the current period of the thread. More...
 
void suspend ()
 Suspend the thread, the thread keeps running by doLoop is never executed. More...
 
void resume ()
 Resume the thread if previously suspended. More...
 
void resetStat ()
 Reset thread statistics. More...
 
double getEstimatedPeriod () const
 Return estimated period since last reset. More...
 
void getEstimatedPeriod (double &av, double &std) const
 Return estimated period since last reset. More...
 
unsigned int getIterations () const
 Return the number of iterations performed since last reset. More...
 
double getEstimatedUsed () const
 Return the estimated duration of the run() function since last reset. More...
 
void getEstimatedUsed (double &av, double &std) const
 Return estimated duration of the run() function since last reset. More...
 
int setPriority (int priority, int policy=-1)
 Set the priority and scheduling policy of the thread, if the OS supports that. More...
 
int getPriority () const
 Query the current priority of the thread, if the OS supports that. More...
 
int getPolicy () const
 Query the current scheduling policy of the thread, if the OS supports that. More...
 
- Public Member Functions inherited from yarp::dev::IMultipleWrapper
virtual ~IMultipleWrapper ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperCommon
bool getAxes (int *ax)
 
bool setRefAcceleration (int j, double acc)
 
bool setRefAccelerations (const double *accs)
 
bool setRefAccelerations (const int n_joints, const int *joints, const double *accs)
 
bool getRefAcceleration (int j, double *acc)
 
bool getRefAccelerations (double *accs)
 
bool getRefAccelerations (const int n_joints, const int *joints, double *accs)
 
bool stop (int j)
 
bool stop ()
 
bool stop (const int n_joint, const int *joints)
 
bool getNumberOfMotors (int *num)
 
bool getCurrent (int m, double *curr)
 
bool getCurrents (double *currs)
 
void printError (const std::string &func_name, const std::string &info, bool result)
 
- Public Member Functions inherited from ControlBoardWrapperPidControl
bool setPid (const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override
 Set new pid value for a joint axis. More...
 
bool setPids (const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *ps) override
 Set new pid value on multiple axes. More...
 
bool setPidReference (const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
 Set the controller reference for a given axis. More...
 
bool setPidReferences (const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
 Set the controller reference, multiple axes. More...
 
bool setPidErrorLimit (const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
 Set the error limit for the controller on a specifi joint. More...
 
bool setPidErrorLimits (const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
 Get the error limit for the controller on all joints. More...
 
bool getPidError (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
 Get the current error for a joint. More...
 
bool getPidErrors (const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
 Get the error of all joints. More...
 
bool getPidOutput (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
 Get the output of the controller (e.g. More...
 
bool getPidOutputs (const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
 Get the output of the controllers (e.g. More...
 
bool setPidOffset (const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
 Set offset value for a given controller. More...
 
bool getPid (const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *p) override
 Get current pid value for a specific joint. More...
 
bool getPids (const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
 Get current pid value for a specific joint. More...
 
bool getPidReference (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override
 Get the current reference of the pid controller for a specific joint. More...
 
bool getPidReferences (const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
 Get the current reference of all pid controllers. More...
 
bool getPidErrorLimit (const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override
 Get the error limit for the controller on a specific joint. More...
 
bool getPidErrorLimits (const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
 Get the error limit for all controllers. More...
 
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. More...
 
bool disablePid (const yarp::dev::PidControlTypeEnum &pidtype, int j) override
 Disable the pid computation for a joint. More...
 
bool enablePid (const yarp::dev::PidControlTypeEnum &pidtype, int j) override
 Enable the pid computation for a joint. More...
 
bool isPidEnabled (const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
 Get the current status (enabled/disabled) of the pid. More...
 
- Public Member Functions inherited from yarp::dev::IPidControl
virtual ~IPidControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperPositionControl
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool positionMove (int j, double ref) override
 Set new reference point for a single axis. More...
 
bool positionMove (const double *refs) override
 Set new reference point for all axes. More...
 
bool positionMove (const int n_joints, const int *joints, const double *refs) override
 Set new reference point for a subset of joints. More...
 
bool getTargetPosition (const int joint, double *ref) override
 Get the last position reference for the specified axis. More...
 
bool getTargetPositions (double *refs) override
 Get the last position reference for all axes. More...
 
bool getTargetPositions (const int n_joint, const int *joints, double *refs) override
 Get the last position reference for the specified group of axes. More...
 
bool relativeMove (int j, double delta) override
 Set relative position. More...
 
bool relativeMove (const double *deltas) override
 Set relative position, all joints. More...
 
bool relativeMove (const int n_joints, const int *joints, const double *deltas) override
 Set relative position for a subset of joints. More...
 
bool checkMotionDone (int j, bool *flag) override
 Check if the current trajectory is terminated. More...
 
bool checkMotionDone (bool *flag) override
 Check if the current trajectory is terminated. More...
 
bool checkMotionDone (const int n_joints, const int *joints, bool *flags) override
 Check if the current trajectory is terminated. More...
 
bool setRefSpeed (int j, double sp) override
 Set reference speed for a joint, this is the speed used during the interpolation of the trajectory. More...
 
bool setRefSpeeds (const double *spds) override
 Set reference speed on all joints. More...
 
bool setRefSpeeds (const int n_joints, const int *joints, const double *spds) override
 Set reference speed on all joints. More...
 
bool setRefAcceleration (int j, double acc) override
 Set reference acceleration for a joint. More...
 
bool setRefAccelerations (const double *accs) override
 Set reference acceleration on all joints. More...
 
bool setRefAccelerations (const int n_joints, const int *joints, const double *accs) override
 Set reference acceleration on all joints. More...
 
bool getRefSpeed (int j, double *ref) override
 Get reference speed for a joint. More...
 
bool getRefSpeeds (double *spds) override
 Get reference speed of all joints. More...
 
bool getRefSpeeds (const int n_joints, const int *joints, double *spds) override
 Get reference speed of all joints. More...
 
bool getRefAcceleration (int j, double *acc) override
 Get reference acceleration for a joint. More...
 
bool getRefAccelerations (double *accs) override
 Get reference acceleration of all joints. More...
 
bool getRefAccelerations (const int n_joints, const int *joints, double *accs) override
 Get reference acceleration for a joint. More...
 
bool stop (int j) override
 Stop motion, single joint. More...
 
bool stop () override
 Stop motion, multiple joints. More...
 
bool stop (const int n_joints, const int *joints) override
 Stop motion for subset of joints. More...
 
- Public Member Functions inherited from yarp::dev::IPositionControl
virtual ~IPositionControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperPositionDirect
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool setPosition (int j, double ref) override
 Set new position for a single axis. More...
 
bool setPositions (const int n_joints, const int *joints, const double *dpos) override
 Set new reference point for all axes. More...
 
bool setPositions (const double *refs) override
 Set new position for a set of axis. More...
 
bool getRefPosition (const int joint, double *ref) override
 Get the last position reference for the specified axis. More...
 
bool getRefPositions (double *refs) override
 Get the last position reference for all axes. More...
 
bool getRefPositions (const int n_joint, const int *joints, double *refs) override
 Get the last position reference for the specified group of axes. More...
 
- Public Member Functions inherited from yarp::dev::IPositionDirect
virtual ~IPositionDirect ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperVelocityControl
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool velocityMove (int j, double v) override
 Start motion at a given speed, single joint. More...
 
bool velocityMove (const double *v) override
 Start motion at a given speed, multiple joints. More...
 
bool velocityMove (const int n_joints, const int *joints, const double *spds) override
 Start motion at a given speed for a subset of joints. More...
 
bool getRefVelocity (const int joint, double *vel) override
 Get the last reference speed set by velocityMove for single joint. More...
 
bool getRefVelocities (double *vels) override
 Get the last reference speed set by velocityMove for all joints. More...
 
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. More...
 
bool setRefAcceleration (int j, double acc) override
 Set reference acceleration for a joint. More...
 
bool setRefAccelerations (const double *accs) override
 Set reference acceleration on all joints. More...
 
bool setRefAccelerations (const int n_joints, const int *joints, const double *accs) override
 Set reference acceleration for a subset of joints. More...
 
bool getRefAcceleration (int j, double *acc) override
 Get reference acceleration for a joint. More...
 
bool getRefAccelerations (double *accs) override
 Get reference acceleration of all joints. More...
 
bool getRefAccelerations (const int n_joints, const int *joints, double *accs) override
 Get reference acceleration for a subset of joints. More...
 
bool stop (int j) override
 Stop motion, single joint. More...
 
bool stop () override
 Stop motion, multiple joints. More...
 
bool stop (const int n_joint, const int *joints) override
 Stop motion for a subset of joints. More...
 
- Public Member Functions inherited from yarp::dev::IVelocityControl
virtual ~IVelocityControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperEncodersTimed
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool resetEncoder (int j) override
 Reset encoder, single joint. More...
 
bool resetEncoders () override
 Reset encoders. More...
 
bool setEncoder (int j, double val) override
 Set the value of the encoder for a given joint. More...
 
bool setEncoders (const double *vals) override
 Set the value of all encoders. More...
 
bool getEncoder (int j, double *v) override
 Read the value of an encoder. More...
 
bool getEncoders (double *encs) override
 Read the position of all axes. More...
 
bool getEncoderSpeed (int j, double *sp) override
 Read the istantaneous speed of an axis. More...
 
bool getEncoderSpeeds (double *spds) override
 Read the instantaneous speed of all axes. More...
 
bool getEncoderAcceleration (int j, double *acc) override
 Read the instantaneous acceleration of an axis. More...
 
bool getEncoderAccelerations (double *accs) override
 Read the instantaneous acceleration of all axes. More...
 
bool getEncodersTimed (double *encs, double *t) override
 Read the instantaneous acceleration of all axes. More...
 
bool getEncoderTimed (int j, double *v, double *t) override
 Read the instantaneous acceleration of all axes. More...
 
- Public Member Functions inherited from yarp::dev::IEncodersTimed
virtual ~IEncodersTimed ()
 Destructor. More...
 
- Public Member Functions inherited from yarp::dev::IEncoders
virtual ~IEncoders ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperMotor
bool getNumberOfMotors (int *num) override
 Get the number of available motors. More...
 
bool getTemperature (int m, double *val) override
 Get temperature of a motor. More...
 
bool getTemperatures (double *vals) override
 Get temperature of all the motors. More...
 
bool getTemperatureLimit (int m, double *val) override
 Retreives the current temperature limit for a specific motor. More...
 
bool setTemperatureLimit (int m, const double val) override
 Set the temperature limit for a specific motor. More...
 
bool getGearboxRatio (int m, double *val) override
 Get the gearbox ratio for a specific motor. More...
 
bool setGearboxRatio (int m, const double val) override
 Set the gearbox ratio for a specific motor. More...
 
- Public Member Functions inherited from yarp::dev::IMotor
virtual ~IMotor ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperMotorEncoders
bool getNumberOfMotorEncoders (int *num) override
 Get the number of available motor encoders. More...
 
bool resetMotorEncoder (int m) override
 Reset motor encoder, single motor. More...
 
bool resetMotorEncoders () override
 Reset motor encoders. More...
 
bool setMotorEncoderCountsPerRevolution (int m, const double cpr) override
 Sets number of counts per revolution for motor encoder m. More...
 
bool getMotorEncoderCountsPerRevolution (int m, double *cpr) override
 Gets number of counts per revolution for motor encoder m. More...
 
bool setMotorEncoder (int m, const double val) override
 Set the value of the motor encoder for a given motor. More...
 
bool setMotorEncoders (const double *vals) override
 Set the value of all motor encoders. More...
 
bool getMotorEncoder (int m, double *v) override
 Read the value of a motor encoder. More...
 
bool getMotorEncoders (double *encs) override
 Read the position of all motor encoders. More...
 
bool getMotorEncodersTimed (double *encs, double *t) override
 Read the instantaneous position of all motor encoders. More...
 
bool getMotorEncoderTimed (int m, double *v, double *t) override
 Read the instantaneous position of a motor encoder. More...
 
bool getMotorEncoderSpeed (int m, double *sp) override
 Read the istantaneous speed of a motor encoder. More...
 
bool getMotorEncoderSpeeds (double *spds) override
 Read the instantaneous speed of all motor encoders. More...
 
bool getMotorEncoderAcceleration (int m, double *acc) override
 Read the instantaneous acceleration of a motor encoder. More...
 
bool getMotorEncoderAccelerations (double *accs) override
 Read the instantaneous acceleration of all motor encoders. More...
 
- Public Member Functions inherited from yarp::dev::IMotorEncoders
virtual ~IMotorEncoders ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperAmplifierControl
bool enableAmp (int j) override
 Enable the amplifier on a specific joint. More...
 
bool disableAmp (int j) override
 Disable the amplifier on a specific joint. More...
 
bool getAmpStatus (int *st) override
 
bool getAmpStatus (int j, int *v) override
 
bool getCurrent (int m, double *curr) override
 
bool getCurrents (double *currs) 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. More...
 
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
 
- Public Member Functions inherited from yarp::dev::IAmplifierControl
virtual ~IAmplifierControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperControlLimits
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. More...
 
bool getLimits (int j, double *min, double *max) override
 Get the software limits for a particular axis. More...
 
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. More...
 
bool getVelLimits (int j, double *min, double *max) override
 Get the software speed limits for a particular axis. More...
 
- Public Member Functions inherited from yarp::dev::IControlLimits
virtual ~IControlLimits ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperRemoteCalibrator
bool isCalibratorDevicePresent (bool *isCalib) override
 isCalibratorDevicePresent: check if a calibrator device has been set More...
 
yarp::dev::IRemoteCalibratorgetCalibratorDevice () override
 getCalibratorDevice: return the pointer stored with the setCalibratorDevice More...
 
bool calibrateSingleJoint (int j) override
 calibrateSingleJoint: call the calibration procedure for the single joint More...
 
bool calibrateWholePart () override
 calibrateWholePart: call the procedure for calibrating the whole device More...
 
bool homingSingleJoint (int j) override
 homingSingleJoint: call the homing procedure for a single joint More...
 
bool homingWholePart () override
 homingWholePart: call the homing procedure for a the whole part/device More...
 
bool parkSingleJoint (int j, bool _wait=true) override
 parkSingleJoint(): start the parking procedure for the single joint More...
 
bool parkWholePart () override
 parkWholePart: start the parking procedure for the whole part More...
 
bool quitCalibrate () override
 quitCalibrate: interrupt the calibration procedure More...
 
bool quitPark () override
 quitPark: interrupt the park procedure More...
 
- Public Member Functions inherited from yarp::dev::IRemoteCalibrator
 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. More...
 
virtual ~IRemoteCalibrator ()=default
 
virtual bool setCalibratorDevice (yarp::dev::IRemoteCalibrator *dev)
 setCalibratorDevice: store the pointer to the calibrator device. More...
 
virtual void releaseCalibratorDevice ()
 releaseCalibratorDevice: reset the internal pointer to NULL when stop using the calibrator More...
 
- Public Member Functions inherited from ControlBoardWrapperControlCalibration
bool calibrateAxisWithParams (int j, unsigned int ui, double v1, double v2, double v3) override
 Start calibration, this method is very often platform specific. More...
 
bool setCalibrationParameters (int j, const yarp::dev::CalibrationParameters &params) override
 Start calibration, this method is very often platform specific. More...
 
bool calibrationDone (int j) override
 Check if the calibration is terminated, on a particular joint. More...
 
bool abortPark () override
 
bool abortCalibration () override
 
- Public Member Functions inherited from yarp::dev::IControlCalibration
 IControlCalibration ()
 
virtual ~IControlCalibration ()
 Destructor. More...
 
virtual bool setCalibrator (ICalibrator *c)
 Set the calibrator object to be used to calibrate the robot. More...
 
virtual bool calibrateRobot ()
 Calibrate robot by using an external calibrator. More...
 
virtual bool park (bool wait=true)
 
- Public Member Functions inherited from ControlBoardWrapperTorqueControl
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool getRefTorques (double *refs) override
 Get the reference value of the torque for all joints. More...
 
bool getRefTorque (int j, double *t) override
 Get the reference value of the torque for a given joint. More...
 
bool setRefTorques (const double *t) override
 Set the reference value of the torque for all joints. More...
 
bool setRefTorque (int j, double t) override
 Set the reference value of the torque for a given joint. More...
 
bool setRefTorques (const int n_joint, const int *joints, const double *t) override
 Set new torque reference for a subset of joints. More...
 
bool getMotorTorqueParams (int j, yarp::dev::MotorTorqueParameters *params) override
 Get a subset of motor parameters (bemf, ktau etc) useful for torque control. More...
 
bool setMotorTorqueParams (int j, const yarp::dev::MotorTorqueParameters params) override
 Set a subset of motor parameters (bemf, ktau etc) useful for torque control. More...
 
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). More...
 
bool getTorques (double *t) override
 Get the value of the torque for all joints (this is the feedback if you have torque sensors). More...
 
bool getTorqueRange (int j, double *min, double *max) override
 Get the full scale of the torque sensor of a given joint. More...
 
bool getTorqueRanges (double *min, double *max) override
 Get the full scale of the torque sensors of all joints. More...
 
- Public Member Functions inherited from yarp::dev::ITorqueControl
virtual ~ITorqueControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperImpedanceControl
bool getAxes (int *ax) override
 Get the number of controlled axes. More...
 
bool setImpedance (int j, double stiff, double damp) override
 Set current impedance gains (stiffness,damping) for a specific joint. More...
 
bool setImpedanceOffset (int j, double offset) override
 Set current force Offset for a specific joint. More...
 
bool getImpedance (int j, double *stiff, double *damp) override
 Get current impedance gains (stiffness,damping,offset) for a specific joint. More...
 
bool getImpedanceOffset (int j, double *offset) override
 Get current force Offset for a specific joint. More...
 
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. More...
 
- Public Member Functions inherited from yarp::dev::IImpedanceControl
virtual ~IImpedanceControl ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperControlMode
bool getControlMode (int j, int *mode) override
 Get the current control mode. More...
 
bool getControlModes (int *modes) override
 Get the current control mode (multiple joints). More...
 
bool getControlModes (const int n_joint, const int *joints, int *modes) override
 Get the current control mode for a subset of axes. More...
 
bool setControlMode (const int j, const int mode) override
 Set the current control mode. More...
 
bool setControlModes (const int n_joints, const int *joints, int *modes) override
 Set the current control mode for a subset of axes. More...
 
bool setControlModes (int *modes) override
 Set the current control mode (multiple joints). More...
 
- Public Member Functions inherited from yarp::dev::IControlMode
virtual ~IControlMode ()
 
- Public Member Functions inherited from ControlBoardWrapperAxisInfo
bool getAxisName (int j, std::string &name) override
 
bool getJointType (int j, yarp::dev::JointTypeEnum &type) override
 
- Public Member Functions inherited from yarp::dev::IAxisInfo
virtual ~IAxisInfo ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperPreciselyTimed
yarp::os::Stamp getLastInputStamp () override
 Return the time stamp relative to the last acquisition. More...
 
- Public Member Functions inherited from yarp::dev::IPreciselyTimed
virtual ~IPreciselyTimed ()
 
- Public Member Functions inherited from ControlBoardWrapperInteractionMode
bool getInteractionMode (int j, yarp::dev::InteractionModeEnum *mode) override
 Get the current interaction mode of the robot, values can be stiff or compliant. More...
 
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. More...
 
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. More...
 
bool setInteractionMode (int j, yarp::dev::InteractionModeEnum mode) override
 Set the interaction mode of the robot, values can be stiff or compliant. More...
 
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. More...
 
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. More...
 
- Public Member Functions inherited from yarp::dev::IInteractionMode
virtual ~IInteractionMode ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperRemoteVariables
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
 
- Public Member Functions inherited from yarp::dev::IRemoteVariables
virtual ~IRemoteVariables ()
 Destructor. More...
 
- Public Member Functions inherited from ControlBoardWrapperPWMControl
bool getNumberOfMotors (int *num) override
 Retrieves the number of controlled motors from the current physical interface. More...
 
bool setRefDutyCycle (int j, double v) override
 Sets the reference dutycycle to a single motor. More...
 
bool setRefDutyCycles (const double *v) override
 Sets the reference dutycycle for all the motors. More...
 
bool getRefDutyCycle (int j, double *v) override
 Gets the last reference sent using the setRefDutyCycle function. More...
 
bool getRefDutyCycles (double *v) override
 Gets the last reference sent using the setRefDutyCycles function. More...
 
bool getDutyCycle (int j, double *v) override
 Gets the current dutycycle of the output of the amplifier (i.e. More...
 
bool getDutyCycles (double *v) override
 Gets the current dutycycle of the output of the amplifier (i.e. More...
 
- Public Member Functions inherited from yarp::dev::IPWMControl
virtual ~IPWMControl ()
 
- Public Member Functions inherited from ControlBoardWrapperCurrentControl
bool getNumberOfMotors (int *num) override
 Retrieves the number of controlled axes from the current physical interface. More...
 
bool getCurrent (int m, double *curr) override
 Get the instantaneous current measurement for a single motor. More...
 
bool getCurrents (double *currs) override
 Get the instantaneous current measurement for all motors. More...
 
bool getCurrentRange (int j, double *min, double *max) override
 Get the full scale of the current measurement for a given motor (e.g. More...
 
bool getCurrentRanges (double *min, double *max) override
 Get the full scale of the current measurements for all motors motor (e.g. More...
 
bool setRefCurrents (const double *t) override
 Set the reference value of the currents for all motors. More...
 
bool setRefCurrent (int j, double t) override
 Set the reference value of the current for a single motor. More...
 
bool setRefCurrents (const int n_joint, const int *joints, const double *t) override
 Set the reference value of the current for a group of motors. More...
 
bool getRefCurrents (double *t) override
 Get the reference value of the currents for all motors. More...
 
bool getRefCurrent (int j, double *t) override
 Get the reference value of the current for a single motor. More...
 
- Public Member Functions inherited from yarp::dev::ICurrentControl
virtual ~ICurrentControl ()
 Destructor. More...
 

Additional Inherited Members

- Public Attributes inherited from ControlBoardWrapperCommon
WrappedDevice device
 
size_t controlledJoints {0}
 
std::string partName
 
std::mutex rpcDataMutex
 
MultiJointData rpcData
 
std::mutex timeMutex
 
yarp::os::Stamp time
 
- Protected Member Functions inherited from yarp::os::PeriodicThread
virtual bool threadInit ()
 Initialization method. More...
 
virtual void threadRelease ()
 Release method. More...
 
virtual void beforeStart ()
 Called just before a new thread starts. More...
 
virtual void afterStart (bool success)
 Called just after a new thread starts (or fails to start), this is executed by the same thread that calls start(). More...
 

Detailed Description

controlboardwrapper2: An updated version of the controlBoard network wrapper.

It can merge together more than one control board device, or use only a portion of it by remapping functionality. Allows also deferred attach/detach of a subdevice.

Description of input parameters

Parameters required by this device are:

Parameter name SubParameter Type Units Default Value Required Description Notes
name - string - - Yes full name of the port opened by the device, like /robotName/part/ MUST start with a '/' character
period - int ms 20 No refresh period of the broadcasted values in ms optional, default 20ms
subdevice - string - - alternative to netwok group name of the subdevice to instantiate when used, parameters for the subdevice must be provided as well
networks - group - - alternative to subdevice this is expected to be a group parameter in xml format, a list in .ini file format. SubParameter are mandatory if this is used -
- networkName_1 4 * int joint number - if networks is used describe how to match subdevice_1 joints with the wrapper joints. First 2 numbers indicate first/last wrapper joint, last 2 numbers are subdevice first/last joint The joints are intended to be consequent
- ... 4 * int joint number - if networks is used same as above The joints are intended to be consequent
- networkName_n 4 * int joint number - if networks is used same as above The joints are intended to be consequent
- joints int - - if networks is used total number of joints handled by the wrapper MUST match the sum of joints from all the networks
ROS - group - - No Group containing parameter for ROS topic initialization if missing, it is assumed to not use ROS topics
- useROS string true/false/only - if ROS group is present set 'true' to have both yarp ports and ROS topic, set 'only' to have only ROS topic and no yarp port -
- ROS_topicName string - - if ROS group is present set the name for ROS topic must start with a leading '/'
- ROS_nodeName string - - if ROS group is present set the name for ROS node must start with a leading '/'
- jointNames string - - deprecated joints names are now got from attached motionControl device names order must match with the joint order, from 0 to N

ROS message type used is sensor_msgs/JointState.msg (http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html) Some example of configuration files:

Configuration file using .ini format, using subdevice keyword.

device controlboardwrapper2
subdevice fakebot
name /icub/head
** parameter for 'fakebot' subdevice follows here **
...

XML format, using 'networks' keyword. This file is meant to be used in junction with yarprobotinterface executable, therefore has an addictional section at the end.

<paramlist name="networks">
<!-- elem name hereafter are custom names that live only in this file, they are used in the attach phase -->
<elem name="FirstSetOfJoints"> 0 3 0 3 </elem>
<elem name="SecondSetOfJoints"> 4 6 0 2 </elem>
</paramlist>
<param name="period"> 20 </param>
<param name="name"> /icub/left_arm </param>
<param name="joints"> 7 </param>
<!-- Following parameters are meaningful ONLY for yarprobotinterface -->
<action phase="startup" level="5" type="attach">
<paramlist name="networks">
<!-- The param value must match the device name in the corresponding emsX file -->
<elem name="FirstSetOfJoints"> left_upper_arm_mc </elem>
<elem name="SecondSetOfJoints"> left_lower_arm_mc </elem>
</paramlist>
</action>
<action phase="shutdown" level="5" type="detach" />

Configuration file using .ini format, using network keyword

device controlboardwrapper2
name /robotName/partName
period 10
networks (net_larm net_lhand)
joints 16
net_larm 0 3 0 3
net_lhand 4 6 0 2

Configuration for ROS topic using .ini format

[ROS]
useROS true
ROS_topicName /JointState
ROS_nodeName /robotPublisher
jointNames r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow r_wrist_prosup r_wrist_pitch r_wrist_yaw

Configuration for ROS topic using .xml format

<group name="ROS">
<param name="useROS"> true </param> // use 'only' if you want only ROS topic and NOT yarp port
<param name="ROS_topicName"> /JointState </param>
<param name="ROS_nodeName"> /robotPublisher </param>
<param name="jointNames"> r_shoulder_pitch r_shoulder_roll r_shoulder_yaw r_elbow r_wrist_prosup r_wrist_pitch r_wrist_yaw </param>
</group>

Definition at line 179 of file ControlBoardWrapper.h.

Constructor & Destructor Documentation

◆ ControlBoardWrapper() [1/3]

ControlBoardWrapper::ControlBoardWrapper ( )

Definition at line 33 of file ControlBoardWrapper.cpp.

◆ ControlBoardWrapper() [2/3]

ControlBoardWrapper::ControlBoardWrapper ( const ControlBoardWrapper )
delete

◆ ControlBoardWrapper() [3/3]

ControlBoardWrapper::ControlBoardWrapper ( ControlBoardWrapper &&  )
delete

◆ ~ControlBoardWrapper()

ControlBoardWrapper::~ControlBoardWrapper ( )
overridedefault

Member Function Documentation

◆ attachAll()

bool ControlBoardWrapper::attachAll ( const yarp::dev::PolyDriverList p)
overridevirtual

Attach to a list of objects.

Parameters
pthe polydriver list that you want to attach to.
Returns
true/false on success failure.

Implements yarp::dev::IMultipleWrapper.

Definition at line 694 of file ControlBoardWrapper.cpp.

◆ close()

bool ControlBoardWrapper::close ( )
overridevirtual

Close the device driver by deallocating all resources and closing ports.

Returns
true if successful or false otherwise.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 62 of file ControlBoardWrapper.cpp.

◆ detachAll()

bool ControlBoardWrapper::detachAll ( )
overridevirtual

Detach the object (you must have first called attach).

Returns
true/false on success failure.

Implements yarp::dev::IMultipleWrapper.

Definition at line 753 of file ControlBoardWrapper.cpp.

◆ getId()

std::string ControlBoardWrapper::getId ( )
inline

Definition at line 269 of file ControlBoardWrapper.h.

◆ open()

bool ControlBoardWrapper::open ( yarp::os::Searchable prop)
overridevirtual

Open the device driver.

Parameters
propis a Searchable object which contains the parameters. Allowed parameters are:
  • name to specify the prefix of the port names.
  • subdevice [optional] if specified, the openAndAttachSubDevice will be called, otherwise openDeferredAttach is called. and all parameters required by the wrapper.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 338 of file ControlBoardWrapper.cpp.

◆ operator=() [1/2]

ControlBoardWrapper& ControlBoardWrapper::operator= ( const ControlBoardWrapper )
delete

◆ operator=() [2/2]

ControlBoardWrapper& ControlBoardWrapper::operator= ( ControlBoardWrapper &&  )
delete

◆ run()

void ControlBoardWrapper::run ( )
overridevirtual

The thread main loop deals with writing on ports here.

Implements yarp::os::PeriodicThread.

Definition at line 777 of file ControlBoardWrapper.cpp.


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