#include <ControlBoardWrapper/ControlBoardWrapper.h>
A 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.
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.
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.
Configuration file using .ini format, using network keyword
Configuration for ROS topic using .ini format
Configuration for ROS topic using .xml format
Definition at line 225 of file ControlBoardWrapper.h.
Public Member Functions | |
ControlBoardWrapper () | |
ControlBoardWrapper (const ControlBoardWrapper &)=delete | |
ControlBoardWrapper (ControlBoardWrapper &&)=delete | |
ControlBoardWrapper & | operator= (const ControlBoardWrapper &)=delete |
ControlBoardWrapper & | operator= (ControlBoardWrapper &&)=delete |
~ControlBoardWrapper () override | |
bool | verbose () const |
Return the value of the verbose flag. More... | |
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... | |
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... | |
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 axis. 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... | |
bool | velocityMove (int j, double v) override |
Set new reference speed for a single axis. More... | |
bool | velocityMove (const double *v) override |
Set a new reference speed for all 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 | 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... | |
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 istantaneous acceleration of all axes. More... | |
bool | getNumberOfMotorEncoders (int *num) override |
Get the number of available motor encoders. More... | |
bool | resetMotorEncoder (int m) override |
Reset encoder, single joint. More... | |
bool | resetMotorEncoders () override |
Reset 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 encoder for a given joint. More... | |
bool | setMotorEncoders (const double *vals) override |
Set the value of all encoders. More... | |
bool | getMotorEncoder (int m, double *v) override |
Read the value of an encoder. More... | |
bool | getMotorEncoders (double *encs) override |
Read the position of all axes. 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 an axis. More... | |
bool | getMotorEncoderSpeeds (double *spds) override |
Read the instantaneous speed of all axes. More... | |
bool | getMotorEncoderAcceleration (int m, double *acc) override |
Read the instantaneous acceleration of an axis. More... | |
bool | getMotorEncoderAccelerations (double *accs) override |
Read the istantaneous acceleration of all axes. More... | |
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 |
Get the status of the amplifiers, coded in a 32 bits integer for each amplifier (at the moment contains only the fault, it will be expanded in the future). More... | |
bool | getAmpStatus (int j, int *v) override |
bool | getCurrents (double *vals) override |
Read the electric current going to all motors. More... | |
bool | getCurrent (int j, double *val) override |
Read the electric current going to a given motor. More... | |
bool | setMaxCurrent (int j, double v) override |
Set the maximum electric current going to a given motor. More... | |
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 |
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 velocity 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 velocity limits for a particular axis. More... | |
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 More... | |
yarp::dev::IRemoteCalibrator * | getCalibratorDevice () 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... | |
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 ¶ms) override |
Start calibration, this method is very often platform specific. More... | |
bool | calibrationDone (int j) override |
Check whether the calibration has been completed. More... | |
bool | abortPark () override |
bool | abortCalibration () override |
bool | getNumberOfMotors (int *num) override |
Retrieves the number of controlled axes from the current physical interface. 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... | |
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. 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 | 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 | 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... | |
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... | |
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... | |
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... | |
yarp::os::Stamp | getLastInputStamp () override |
Return the time stamp relative to the last acquisition. 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 | 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... | |
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... | |
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... | |
![]() | |
~DeviceDriver () override=default | |
Destructor. More... | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. More... | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. More... | |
![]() | |
virtual | ~IConfig () |
Destructor. More... | |
virtual bool | configure (Searchable &config) |
Change online parameters. More... | |
![]() | |
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... | |
![]() | |
virtual | ~IPidControl () |
Destructor. More... | |
![]() | |
virtual | ~IPositionControl () |
Destructor. More... | |
![]() | |
virtual | ~IPositionDirect () |
Destructor. More... | |
![]() | |
virtual | ~IVelocityControl () |
Destructor. More... | |
![]() | |
virtual | ~IEncodersTimed () |
Destructor. More... | |
![]() | |
virtual | ~IEncoders () |
Destructor. More... | |
![]() | |
virtual | ~IMotor () |
Destructor. More... | |
![]() | |
virtual | ~IMotorEncoders () |
Destructor. More... | |
![]() | |
virtual | ~IAmplifierControl () |
Destructor. More... | |
![]() | |
virtual | ~IControlLimits () |
Destructor. More... | |
![]() | |
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... | |
![]() | |
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) |
![]() | |
virtual | ~ITorqueControl () |
Destructor. More... | |
![]() | |
virtual | ~IImpedanceControl () |
Destructor. More... | |
![]() | |
virtual | ~IControlMode () |
![]() | |
virtual | ~IMultipleWrapper () |
Destructor. More... | |
![]() | |
virtual | ~IAxisInfo () |
Destructor. More... | |
![]() | |
virtual | ~IPreciselyTimed () |
![]() | |
virtual | ~IInteractionMode () |
Destructor. More... | |
![]() | |
virtual | ~IRemoteVariables () |
Destructor. More... | |
![]() | |
virtual | ~IPWMControl () |
![]() | |
virtual | ~ICurrentControl () |
Destructor. More... | |
Additional Inherited Members | |
![]() | |
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... | |
ControlBoardWrapper::ControlBoardWrapper | ( | ) |
Definition at line 31 of file ControlBoardWrapper.cpp.
|
delete |
|
delete |
|
overridedefault |
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3708 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3702 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Attach to a list of objects.
p | the polydriver list that you want to attach to. |
Implements yarp::dev::IMultipleWrapper.
Definition at line 786 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Implements yarp::dev::IControlCalibration.
Definition at line 3660 of file ControlBoardWrapper.cpp.
|
overridevirtual |
calibrateSingleJoint: call the calibration procedure for the single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3587 of file ControlBoardWrapper.cpp.
|
overridevirtual |
calibrateWholePart: call the procedure for calibrating the whole device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3595 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Check whether the calibration has been completed.
j | is the joint that has started a calibration procedure. |
Implements yarp::dev::IControlCalibration.
Definition at line 3686 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
flag | true if the trajectory is terminated, false otherwise (a single value which is the 'and' of all joints') |
Non blocking.
flag | true if the trajectory is terminated, false otherwise |
Implements yarp::dev::IPositionControl.
Definition at line 1759 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
joints | pointer to the array of joint numbers |
flag | true if the trajectory is terminated, false otherwise (a single value which is the 'and' of all joints') |
Implements yarp::dev::IPositionControl.
Definition at line 1808 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
j | the axis |
flag | true if the trajectory is terminated, false otherwise |
Implements yarp::dev::IPositionControl.
Definition at line 1737 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Close the device driver by deallocating all resources and closing ports.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 73 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Detach the object (you must have first called attach).
Implements yarp::dev::IMultipleWrapper.
Definition at line 853 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Disable the amplifier on a specific joint.
All computations within the board will be carried out normally, but the output will be disabled.
Implements yarp::dev::IAmplifierControl.
Definition at line 3240 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Disable the pid computation for a joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
Implements yarp::dev::IPidControl.
Definition at line 1363 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Enable the amplifier on a specific joint.
Be careful, check that the output of the controller is appropriate (usually zero), to avoid generating abrupt movements.
Implements yarp::dev::IAmplifierControl.
Definition at line 3224 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Enable the pid computation for a joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
Implements yarp::dev::IPidControl.
Definition at line 1378 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the status of the amplifiers, coded in a 32 bits integer for each amplifier (at the moment contains only the fault, it will be expanded in the future).
st | pointer to storage |
Implements yarp::dev::IAmplifierControl.
Definition at line 3265 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 3297 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the number of controlled axes.
This command asks the number of controlled axes for the current physical interface.
ax | pointer to storage |
Implements yarp::dev::IImpedanceControl.
Definition at line 1419 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAxisInfo.
Definition at line 3716 of file ControlBoardWrapper.cpp.
|
overridevirtual |
getCalibratorDevice: return the pointer stored with the setCalibratorDevice
Reimplemented from yarp::dev::IRemoteCalibrator.
Definition at line 3575 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current control mode.
j | joint number |
mode | a vocab of the current control mode for joint j. |
Implements yarp::dev::IControlMode.
Definition at line 4091 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current control mode for a subset of axes.
n_joints | how many joints this command is referring to |
joints | list of joint numbers, the size of this array is n_joints |
modes | array containing the new controlmodes, one value for each joint, the size is n_joints. The first value will be the new reference for the joint joints[0]. for example: n_joint 3 joints 0 2 4 modes VOCAB_CM_POSITION VOCAB_CM_VELOCITY VOCAB_CM_POSITION |
Implements yarp::dev::IControlMode.
Definition at line 4141 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current control mode (multiple joints).
modes | a vector containing vocabs for the current control modes of the joints. |
Implements yarp::dev::IControlMode.
Definition at line 4107 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the electric current going to a given motor.
j | motor number |
val | pointer to storage for the output value |
Implements yarp::dev::IAmplifierControl.
Definition at line 4959 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current impedandance limits for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 4074 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the full scale of the current measurement for a given motor (e.g.
-20A +20A) Reference values set by user with methods such as setRefCurrent() should be in this range. This method is not related to the current overload protection methods belonging to the iAmplifierControl interface.
m | motor number |
min | minimum current of the motor m |
max | maximum current of the motor m |
Implements yarp::dev::ICurrentControl.
Definition at line 4980 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the full scale of the current measurements for all motors motor (e.g.
-20A +20A) Reference values set by user with methods such as setRefCurrent() should be in this range. This method is not related to the current overload protection methods belonging to the iAmplifierControl interface.
min | pointer to the array that will store minimum currents |
max | pointer to the array that will store maximum currents |
Implements yarp::dev::ICurrentControl.
Definition at line 4998 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the electric current going to all motors.
vals | pointer to storage for the output values |
Implements yarp::dev::IAmplifierControl.
Definition at line 4920 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Gets the current dutycycle of the output of the amplifier (i.e.
pwm value sent to the motor)
m | motor number |
val | pointer to storage for return value, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4863 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Gets the current dutycycle of the output of the amplifier (i.e.
pwm values sent to all motors)
vals | pointer to the vector that will store the values, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4880 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the value of an encoder.
j | encoder number |
v | pointer to storage for the return value |
Implements yarp::dev::IEncoders.
Definition at line 2535 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of an axis.
j | axis number |
acc | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 2683 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the istantaneous acceleration of all axes.
accs | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 2699 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the position of all axes.
encs | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 2551 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the istantaneous speed of an axis.
j | axis number |
sp | pointer to storage for the output |
Implements yarp::dev::IEncoders.
Definition at line 2635 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous speed of all axes.
spds | pointer to storage for the output values |
Implements yarp::dev::IEncoders.
Definition at line 2651 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of all axes.
encs | pointer to the array that will contain the output |
time | pointer to the array that will contain individual timestamps |
Implements yarp::dev::IEncodersTimed.
Definition at line 2584 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of all axes.
j | axis index |
encs | encoder value (pointer to) |
time | corresponding timestamp (pointer to) |
Implements yarp::dev::IEncodersTimed.
Definition at line 2619 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the gearbox ratio for a specific motor.
m | motor number |
val | retrieved gearbox ratio |
Reimplemented from yarp::dev::IMotor.
Definition at line 2816 of file ControlBoardWrapper.cpp.
|
inline |
Definition at line 344 of file ControlBoardWrapper.h.
|
overridevirtual |
Get current impedance gains (stiffness,damping,offset) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 4040 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 4057 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current interaction mode of the robot, values can be stiff or compliant.
axis | joint number |
mode | contains the requested information about interaction mode of the joint |
Implements yarp::dev::IInteractionMode.
Definition at line 4594 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant.
n_joints | how many joints this command is referring to |
joints | list of joints controlled. The size of this array is n_joints |
modes | array containing the requested information about interaction mode, one value for each joint, the size is n_joints. for example: n_joint 3 joints 0 2 4 refs VOCAB_IM_STIFF VOCAB_IM_STIFF VOCAB_IM_COMPLIANT |
Implements yarp::dev::IInteractionMode.
Definition at line 4610 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current interaction mode of the robot for a all the joints, values can be stiff or compliant.
mode | array containing the requested information about interaction mode, one value for each joint. |
Implements yarp::dev::IInteractionMode.
Definition at line 4666 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAxisInfo.
Definition at line 3732 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Return the time stamp relative to the last acquisition.
Implements yarp::dev::IPreciselyTimed.
Definition at line 4332 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the software limits for a particular axis.
j | joint number |
min | pointer to store the value of the lower limit |
max | pointer to store the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 3515 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Returns the maximum electric current allowed for a given motor.
The behavior of the board/amplifier when this limit is reached depends on the implementation.
j | motor number |
v | the return value |
Implements yarp::dev::IAmplifierControl.
Definition at line 3327 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the value of an encoder.
j | encoder number |
v | pointer to storage for the return value |
Implements yarp::dev::IMotorEncoders.
Definition at line 3019 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of an axis.
j | axis number |
acc | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 3167 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the istantaneous acceleration of all axes.
accs | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 3183 of file ControlBoardWrapper.cpp.
|
overridevirtual |
gets number of counts per revolution for motor encoder m.
m | motor encoder number |
cpr | pointer to storage for the return value |
Implements yarp::dev::IMotorEncoders.
Definition at line 3003 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the position of all axes.
encs | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 3035 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the istantaneous speed of an axis.
j | axis number |
sp | pointer to storage for the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 3119 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous speed of all axes.
spds | pointer to storage for the output values |
Implements yarp::dev::IMotorEncoders.
Definition at line 3135 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous position of all motor encoders.
encs | pointer to the array that will contain the output |
time | pointer to the array that will contain individual timestamps |
Implements yarp::dev::IMotorEncoders.
Definition at line 3068 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Read the instantaneous position of a motor encoder.
m | motor index |
encs | encoder value (pointer to) |
time | corresponding timestamp (pointer to) |
Implements yarp::dev::IMotorEncoders.
Definition at line 3103 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
j | joint number |
params | a struct containing the motor parameters to be retrieved |
Reimplemented from yarp::dev::ITorqueControl.
Definition at line 3871 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3347 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the number of available motor encoders.
m | pointer to a value representing the number of available motor encoders. |
Implements yarp::dev::IMotorEncoders.
Definition at line 3217 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Retrieves the number of controlled axes from the current physical interface.
ax | returns the number of controlled axes. |
Implements yarp::dev::ICurrentControl.
Definition at line 2732 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3367 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get current pid value for a specific joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
pid | pointer to storage for the return value. |
Implements yarp::dev::IPidControl.
Definition at line 1206 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current error for a joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
err | pointer to the storage for the return value |
Implements yarp::dev::IPidControl.
Definition at line 1092 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the error limit for the controller on a specific joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
limit | pointer to storage |
Implements yarp::dev::IPidControl.
Definition at line 1301 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the error limit for all controllers.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
limits | pointer to the array that will store the output |
Implements yarp::dev::IPidControl.
Definition at line 1316 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the error of all joints.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
errs | pointer to the vector that will store the errors |
Implements yarp::dev::IPidControl.
Definition at line 1109 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the output of the controller (e.g.
pwm value)
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
out | pointer to storage for return value |
Implements yarp::dev::IPidControl.
Definition at line 1141 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the output of the controllers (e.g.
pwm value)
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
outs | pinter to the vector that will store the output values |
Implements yarp::dev::IPidControl.
Definition at line 1158 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current reference of the pid controller for a specific joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
ref | pointer to storage for return value |
Implements yarp::dev::IPidControl.
Definition at line 1255 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current reference of all pid controllers.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
refs | vector that will store the output. |
Implements yarp::dev::IPidControl.
Definition at line 1269 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get current pid value for a specific joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
pids | vector that will store the values of the pids. |
Implements yarp::dev::IPidControl.
Definition at line 1223 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3476 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3419 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3439 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference acceleration for a joint.
Returns the acceleration used to generate the trajectory profile.
j | joint number |
acc | pointer to storage for the return value |
Implements yarp::dev::IPositionControl.
Definition at line 2197 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference acceleration for a joint.
Returns the acceleration used to generate the trajectory profile.
joints | pointer to the array of joint numbers |
accs | pointer to the array that will store the acceleration values |
Implements yarp::dev::IPositionControl.
Definition at line 2259 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference acceleration of all joints.
These are the values used during the interpolation of the trajectory.
accs | pointer to the array that will store the acceleration values. |
Implements yarp::dev::IPositionControl.
Definition at line 2220 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the reference value of the current for a single motor.
m | motor number |
curr | the current reference value for motor m. Value is expressed in amperes. |
Implements yarp::dev::ICurrentControl.
Definition at line 5142 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the reference value of the currents for all motors.
currs | pointer to the array to be filled with reference current values. Values are expressed in amperes. |
Implements yarp::dev::ICurrentControl.
Definition at line 5109 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Gets the last reference sent using the setRefDutyCycle function.
m | motor number |
ref | pointer to storage for return value, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4813 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Gets the last reference sent using the setRefDutyCycles function.
refs | pointer to the vector that will store the values, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4830 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for the specified axis.
This is the dual of setPositions and shall return only values sent using IPositionDirect interface. If other interfaces like IPositionControl are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionControl::PositionMove.
ref | last reference sent using setPosition(s) functions |
Reimplemented from yarp::dev::IPositionDirect.
Definition at line 4339 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for the specified group of axes.
This is the dual of setPositions and shall return only values sent using IPositionDirect interface. If other interfaces like IPositionControl are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionControl::PositionMove.
ref | array containing last reference sent using setPosition(s) functions |
Reimplemented from yarp::dev::IPositionDirect.
Definition at line 4392 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for all axes.
This is the dual of setPositions and shall return only values sent using IPositionDirect interface. If other interfaces like IPositionControl are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionControl::PositionMove.
ref | array containing last reference sent using setPosition(s) functions |
Reimplemented from yarp::dev::IPositionDirect.
Definition at line 4358 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference speed for a joint.
Returns the speed used to generate the trajectory profile.
j | joint number |
ref | pointer to storage for the return value |
Implements yarp::dev::IPositionControl.
Definition at line 2073 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference speed of all joints.
These are the values used during the interpolation of the trajectory.
joints | pointer to the array of joint numbers |
spds | pointer to the array that will store the speed values. |
Implements yarp::dev::IPositionControl.
Definition at line 2135 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get reference speed of all joints.
These are the values used during the interpolation of the trajectory.
spds | pointer to the array that will store the speed values. |
Implements yarp::dev::IPositionControl.
Definition at line 2096 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the reference value of the torque for a given joint.
This is NOT the feedback (see getTorque instead).
j | joint number |
t | the returned reference torque of joint j |
Implements yarp::dev::ITorqueControl.
Definition at line 3780 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the reference value of the torque for all joints.
This is NOT the feedback (see getTorques instead).
t | pointer to the array of torque values |
Implements yarp::dev::ITorqueControl.
Definition at line 3748 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last reference speed set by velocityMove for a group of joints.
n_joint | how many joints this command is referring to |
joints | of joints controlled. The size of this array is n_joints |
vels | pointer to the array containing the requested values, one value for each joint. The size of the array is n_joints. |
Reimplemented from yarp::dev::IVelocityControl.
Definition at line 4539 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last reference speed set by velocityMove for all joints.
vels | pointer to the array containing the new speed values, one value for each joint |
Reimplemented from yarp::dev::IVelocityControl.
Definition at line 4506 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last reference speed set by velocityMove for single joint.
j | joint number |
vel | returns the requested reference. |
Reimplemented from yarp::dev::IVelocityControl.
Definition at line 4483 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2848 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2896 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for the specified axis.
This is the dual of PositionMove and shall return only values sent using IPositionControl interface. If other interfaces like IPositionDirect are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionDirect::SetPosition
ref | last reference sent using PositionMove functions |
Reimplemented from yarp::dev::IPositionControl.
Definition at line 1533 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for the specified group of axes.
This is the dual of PositionMove and shall return only values sent using IPositionControl interface. If other interfaces like IPositionDirect are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionDirect::SetPosition
ref | last reference sent using PositionMove functions |
Reimplemented from yarp::dev::IPositionControl.
Definition at line 1591 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the last position reference for all axes.
Get reference speed of all joints.
This is the dual of PositionMove and shall return only values sent using IPositionControl interface. If other interfaces like IPositionDirect are implemented by the device, this call must ignore their values, i.e. this call must never return a reference sent using IPositionDirect::SetPosition
ref | last reference sent using PositionMove functions |
These are the values used during the interpolation of the trajectory.
spds | pointer to the array that will store the speed values. |
Reimplemented from yarp::dev::IPositionControl.
Definition at line 1558 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get temperature of a motor.
m | motor number |
val | retrieved motor temperature |
Implements yarp::dev::IMotor.
Definition at line 2737 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Retreives the current temperature limit for a specific motor.
The specific behavior of the motor when the temperature limit is exceeded depends on the implementation (power off recommended)
m | motor number |
temp | the current temperature limit. |
Implements yarp::dev::IMotor.
Definition at line 2785 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get temperature of all the motors.
vals | pointer to an array containing all motor temperatures |
Implements yarp::dev::IMotor.
Definition at line 2753 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor).
j | joint number |
t | pointer to the result value |
Implements yarp::dev::ITorqueControl.
Definition at line 3937 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the full scale of the torque sensor of a given joint.
j | joint number |
min | minimum torque of the joint j |
max | maximum torque of the joint j |
Implements yarp::dev::ITorqueControl.
Definition at line 3987 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the full scale of the torque sensors of all joints.
min | pointer to the array that will store minimum torques of the joints |
max | pointer to the array that will store maximum torques of the joints |
Implements yarp::dev::ITorqueControl.
Definition at line 4004 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
t | pointer to the array that will store the output |
Implements yarp::dev::ITorqueControl.
Definition at line 3954 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the software velocity limits for a particular axis.
j | joint number |
min | pointer to store the value of the lower limit |
max | pointer to store the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 3553 of file ControlBoardWrapper.cpp.
|
overridevirtual |
homingSingleJoint: call the homing procedure for a single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3604 of file ControlBoardWrapper.cpp.
|
overridevirtual |
homingWholePart: call the homing procedure for a the whole part/device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3613 of file ControlBoardWrapper.cpp.
|
overridevirtual |
isCalibratorDevicePresent: check if a calibrator device has been set
Reimplemented from yarp::dev::IRemoteCalibrator.
Definition at line 3581 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the current status (enabled/disabled) of the pid.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
enabled | the current status of the pid controller. |
Implements yarp::dev::IPidControl.
Definition at line 1393 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Open the device driver.
prop | is a Searchable object which contains the parameters. Allowed parameters are:
|
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 391 of file ControlBoardWrapper.cpp.
|
delete |
|
delete |
|
overridevirtual |
parkSingleJoint(): start the parking procedure for the single joint
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3622 of file ControlBoardWrapper.cpp.
|
overridevirtual |
parkWholePart: start the parking procedure for the whole part
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3631 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new reference point for all axes.
refs | array, new reference points. |
Implements yarp::dev::IPositionControl.
Definition at line 1450 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new reference point for a subset of axis.
joints | pointer to the array of joint numbers |
refs | pointer to the array specifying the new reference points |
Implements yarp::dev::IPositionControl.
Definition at line 1498 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new reference point for a single axis.
j | joint number |
ref | specifies the new ref point |
Implements yarp::dev::IPositionControl.
Definition at line 1430 of file ControlBoardWrapper.cpp.
|
overridevirtual |
quitCalibrate: interrupt the calibration procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3640 of file ControlBoardWrapper.cpp.
|
overridevirtual |
quitPark: interrupt the park procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3649 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set relative position, all joints.
deltas | pointer to the relative commands |
Implements yarp::dev::IPositionControl.
Definition at line 1669 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set relative position for a subset of joints.
joints | pointer to the array of joint numbers |
deltas | pointer to the array of relative commands |
Implements yarp::dev::IPositionControl.
Definition at line 1696 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set relative position.
The command is relative to the current position of the axis.
j | joint axis number |
delta | relative command |
Implements yarp::dev::IPositionControl.
Definition at line 1649 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reset encoder, single joint.
Set the encoder value to zero
j | is the axis number |
Implements yarp::dev::IEncoders.
Definition at line 2461 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reset encoders.
Set the encoder values to zero for all axes
Implements yarp::dev::IEncoders.
Definition at line 2476 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reset encoder, single joint.
Set the encoder value to zero
j | is the axis number |
Implements yarp::dev::IMotorEncoders.
Definition at line 2914 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reset encoders.
Set the encoder values to zero for all axes
Implements yarp::dev::IMotorEncoders.
Definition at line 2929 of file ControlBoardWrapper.cpp.
|
overridevirtual |
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.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
Implements yarp::dev::IPidControl.
Definition at line 1348 of file ControlBoardWrapper.cpp.
|
overridevirtual |
The thread main loop deals with writing on ports here.
Implements yarp::os::PeriodicThread.
Definition at line 873 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3673 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the current control mode.
j | joint number |
mode | a vocab of the desired control mode for joint j. |
Implements yarp::dev::IControlMode.
Definition at line 4164 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the current control mode for a subset of axes.
n_joints | how many joints this command is referring to |
joints | list of joint numbers, the size of this array is n_joints |
modes | array containing the new controlmodes, one value for each joint, the size is n_joints. The first value will be the new reference for the joint joints[0]. for example: n_joint 3 joints 0 2 4 modes VOCAB_CM_POSITION VOCAB_CM_VELOCITY VOCAB_CM_POSITION |
Implements yarp::dev::IControlMode.
Definition at line 4181 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the current control mode (multiple joints).
modes | a vector containing vocabs for the desired control modes of the joints. |
Implements yarp::dev::IControlMode.
Definition at line 4216 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the value of the encoder for a given joint.
j | encoder number |
val | new value |
Implements yarp::dev::IEncoders.
Definition at line 2498 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the value of all encoders.
vals | pointer to the new values |
Implements yarp::dev::IEncoders.
Definition at line 2513 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the gearbox ratio for a specific motor.
m | motor number |
gearbox | ratio to be set |
Reimplemented from yarp::dev::IMotor.
Definition at line 2832 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set current impedance gains (stiffness,damping) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3903 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3920 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the interaction mode of the robot, values can be stiff or compliant.
Please note that some robot may not implement certain types of interaction, so always check the return value.
axis | joint number |
mode | the desired interaction mode |
Implements yarp::dev::IInteractionMode.
Definition at line 4699 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the interaction mode of the robot for a set of joints, values can be stiff or compliant.
Please note that some robot may not implement certain types of interaction, so always check the return value.
n_joints | how many joints this command is referring to |
joints | list of joints controlled. The size of this array is n_joints |
modes | array containing the desired interaction mode, one value for each joint, the size is n_joints. for example: n_joint 3 joints 0 2 4 refs VOCAB_IM_STIFF VOCAB_IM_STIFF VOCAB_IM_COMPLIANT |
Implements yarp::dev::IInteractionMode.
Definition at line 4715 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the interaction mode of the robot for a all the joints, values can be stiff or compliant.
Some robot may not implement some types of interaction, so always check the return value
mode | array with the desired interaction mode for all joints, length is the total number of joints for the part |
Implements yarp::dev::IInteractionMode.
Definition at line 4750 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the software limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation.
j | joint number (why am I telling you this) |
min | the value of the lower limit |
max | the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 3499 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the maximum electric current going to a given motor.
The behavior of the board/amplifier when this limit is reached depends on the implementation.
j | motor number |
v | the new value |
Implements yarp::dev::IAmplifierControl.
Definition at line 3311 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the value of the encoder for a given joint.
j | encoder number |
val | new value |
Implements yarp::dev::IMotorEncoders.
Definition at line 2951 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Sets number of counts per revolution for motor encoder m.
m | motor encoder number |
cpr | new parameter |
Implements yarp::dev::IMotorEncoders.
Definition at line 2988 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the value of all encoders.
vals | pointer to the new values |
Implements yarp::dev::IMotorEncoders.
Definition at line 2966 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
j | joint number |
params | a struct containing the motor parameters to be set |
Reimplemented from yarp::dev::ITorqueControl.
Definition at line 3887 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3403 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3387 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new pid value for a joint axis.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
pid | new pid value |
Implements yarp::dev::IPidControl.
Definition at line 975 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the error limit for the controller on a specifi joint.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
limit | limit value |
Implements yarp::dev::IPidControl.
Definition at line 1053 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Get the error limit for the controller on all joints.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
limits | pointer to the vector with the new limits |
Implements yarp::dev::IPidControl.
Definition at line 1069 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set offset value for a given controller.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
v | the offset to be added to the output of the pid controller |
Implements yarp::dev::IPidControl.
Definition at line 1190 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the controller reference for a given axis.
Warning this method can result in very large torques and should be used carefully. If you do not understand this warning you should avoid using this method. Have a look at other interfaces (e.g. position control).
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
ref | new reference point |
Implements yarp::dev::IPidControl.
Definition at line 1014 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the controller reference, multiple axes.
Warning this method can result in very large torques and should be used carefully. If you do not understand this warning you should avoid using this method. Have a look at other interfaces (e.g. position control).
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
refs | pointer to the vector that contains the new reference points. |
Implements yarp::dev::IPidControl.
Definition at line 1030 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new pid value on multiple axes.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
pids | pointer to a vector of pids |
Implements yarp::dev::IPidControl.
Definition at line 991 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new position for a single axis.
j | joint number |
ref | specifies the new ref point |
Implements yarp::dev::IPositionDirect.
Definition at line 4255 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new position for a set of axis.
refs | specifies the new reference points |
Implements yarp::dev::IPositionDirect.
Definition at line 4309 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new reference point for all axes.
n_joint | how many joints this command is referring to |
joints | list of joints controlled. The size of this array is n_joints |
refs | array, new reference points, one value for each joint, the size is n_joints. The first value will be the new reference for the joint joints[0]. for example: n_joint 3 joints 0 2 4 refs 10 30 40 |
Implements yarp::dev::IPositionDirect.
Definition at line 4272 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 3460 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference acceleration for a joint.
This value is used during the trajectory generation.
j | joint number |
acc | acceleration value |
Implements yarp::dev::IPositionControl.
Definition at line 1963 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference acceleration on all joints.
This is the valure that is used during the generation of the trajectory.
accs | pointer to the array of acceleration values |
Implements yarp::dev::IPositionControl.
Definition at line 1984 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference acceleration on all joints.
This is the valure that is used during the generation of the trajectory.
joints | pointer to the array of joint numbers |
accs | pointer to the array with acceleration values |
Implements yarp::dev::IPositionControl.
Definition at line 2030 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the reference value of the current for a single motor.
m | motor number |
curr | the current reference value for motor m. Value is expressed in amperes. |
Implements yarp::dev::ICurrentControl.
Definition at line 5057 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the reference value of the currents for all motors.
currs | the array containing the reference current values. Values are expressed in amperes. |
Implements yarp::dev::ICurrentControl.
Definition at line 5034 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the reference value of the current for a group of motors.
n_motor | size of motors ans currs arrays |
motors | pointer to the array containing the list of motor numbers |
currs | pointer to the array specifying the new current references |
Implements yarp::dev::ICurrentControl.
Definition at line 5074 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Sets the reference dutycycle to a single motor.
m | motor number |
ref | the dutycycle, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4773 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Sets the reference dutycycle for all the motors.
refs | the dutycycle, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 4790 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
j | joint number |
sp | speed value |
Implements yarp::dev::IPositionControl.
Definition at line 1855 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference speed on all joints.
These values are used during the interpolation of the trajectory.
spds | pointer to the array of speed values. |
Implements yarp::dev::IPositionControl.
Definition at line 1875 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set reference speed on all joints.
These values are used during the interpolation of the trajectory.
joints | pointer to the array of joint numbers |
spds | pointer to the array with speed values. |
Implements yarp::dev::IPositionControl.
Definition at line 1921 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the reference value of the torque for a given joint.
j | joint number |
t | new value |
Implements yarp::dev::ITorqueControl.
Definition at line 3820 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the reference value of the torque for all joints.
t | pointer to the array of torque values |
Implements yarp::dev::ITorqueControl.
Definition at line 3797 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new torque reference for a subset of joints.
joints | pointer to the array of joint numbers |
refs | pointer to the array specifying the new torque reference |
Reimplemented from yarp::dev::ITorqueControl.
Definition at line 3836 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2865 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the temperature limit for a specific motor.
The specific behavior of the motor when the temperature limit is exceeded depends on the implementation (power off recommended)
m | motor number |
temp | the temperature limit to be set |
Implements yarp::dev::IMotor.
Definition at line 2801 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set the software velocity limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation.
j | joint number |
min | the value of the lower limit |
max | the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 3537 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Stop motion, multiple joints.
Implements yarp::dev::IPositionControl.
Definition at line 2340 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Stop motion for subset of joints.
joints | pointer to the array of joint numbers |
Implements yarp::dev::IPositionControl.
Definition at line 2368 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Stop motion, single joint.
j | joint number |
Implements yarp::dev::IPositionControl.
Definition at line 2319 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set a new reference speed for all axes.
v | is a vector of double representing the requested speed. |
Implements yarp::dev::IVelocityControl.
Definition at line 2420 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Start motion at a given speed for a subset of joints.
n_joint | how many joints this command is referring to |
joints | of joints controlled. The size of this array is n_joints |
spds | pointer to the array containing the new speed values, one value for each joint, the size of the array is n_joints. The first value will be the new reference for the joint joints[0]. for example: n_joint 3 joints 0 2 4 spds 10 30 40 |
Implements yarp::dev::IVelocityControl.
Definition at line 4448 of file ControlBoardWrapper.cpp.
|
overridevirtual |
Set new reference speed for a single axis.
j | joint number |
v | specifies the new ref speed |
Implements yarp::dev::IVelocityControl.
Definition at line 2404 of file ControlBoardWrapper.cpp.
|
inline |
Return the value of the verbose flag.
Definition at line 338 of file ControlBoardWrapper.h.