controlboardremapper
: device that takes a list of axes from multiple controlboards and expose them as a single controlboard.
More...
#include <ControlBoardRemapper/ControlBoardRemapper.h>
Public Member Functions | |
ControlBoardRemapper ()=default | |
ControlBoardRemapper (const ControlBoardRemapper &)=delete | |
ControlBoardRemapper (ControlBoardRemapper &&)=delete | |
ControlBoardRemapper & | operator= (const ControlBoardRemapper &)=delete |
ControlBoardRemapper & | operator= (ControlBoardRemapper &&)=delete |
~ControlBoardRemapper () override=default | |
bool | verbose () const |
Return the value of the verbose flag. More... | |
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... | |
bool | setPid (const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override |
ControlBoard methods. 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 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... | |
bool | getLastJointFault (int j, int &fault, std::string &message) override |
bool | velocityMove (int j, double v) override |
Start motion at a given speed, single joint. More... | |
bool | velocityMove (const double *v) override |
Start motion at a given speed, multiple joints. 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 instantaneous acceleration of all axes. More... | |
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... | |
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 | 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 |
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... | |
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 if the calibration is terminated, on a particular joint. 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 m, double ref) override |
Sets the reference dutycycle to a single motor. More... | |
bool | setRefDutyCycles (const double *refs) override |
Sets the reference dutycycle for all the motors. More... | |
bool | getRefDutyCycle (int m, double *ref) override |
Gets the last reference sent using the setRefDutyCycle function. More... | |
bool | getRefDutyCycles (double *refs) override |
Gets the last reference sent using the setRefDutyCycles function. More... | |
bool | getDutyCycle (int m, double *val) override |
Gets the current dutycycle of the output of the amplifier (i.e. More... | |
bool | getDutyCycles (double *vals) override |
Gets the current dutycycle of the output of the amplifier (i.e. More... | |
bool | getCurrent (int m, double *curr) override |
bool | getCurrents (double *currs) override |
bool | getCurrentRange (int m, 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 *currs) override |
Set the reference value of the currents for all motors. More... | |
bool | setRefCurrent (int m, double curr) override |
Set the reference value of the current for a single motor. More... | |
bool | setRefCurrents (const int n_motor, const int *motors, const double *currs) override |
Set the reference value of the current for a group of motors. More... | |
bool | getRefCurrents (double *currs) override |
Get the reference value of the currents for all motors. More... | |
bool | getRefCurrent (int m, double *curr) override |
Get the reference value of the current for a single motor. More... | |
![]() | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
~DeviceDriver () override | |
bool | open (yarp::os::Searchable &config) override |
Open the DeviceDriver. More... | |
bool | close () override |
Close the DeviceDriver. More... | |
virtual std::string | id () const |
Return the id assigned to the PolyDriver. More... | |
virtual void | setId (const std::string &id) |
Set the id for this device. 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 | open (Searchable &config) |
Initialize the object. More... | |
virtual bool | close () |
Shut the object down. More... | |
virtual bool | configure (Searchable &config) |
Change online parameters. More... | |
![]() | |
virtual | ~IPidControl () |
Destructor. More... | |
virtual bool | setPid (const PidControlTypeEnum &pidtype, int j, const Pid &pid)=0 |
Set new pid value for a joint axis. More... | |
virtual bool | setPids (const PidControlTypeEnum &pidtype, const Pid *pids)=0 |
Set new pid value on multiple axes. More... | |
virtual bool | setPidReference (const PidControlTypeEnum &pidtype, int j, double ref)=0 |
Set the controller reference for a given axis. More... | |
virtual bool | setPidReferences (const PidControlTypeEnum &pidtype, const double *refs)=0 |
Set the controller reference, multiple axes. More... | |
virtual bool | setPidErrorLimit (const PidControlTypeEnum &pidtype, int j, double limit)=0 |
Set the error limit for the controller on a specifi joint. More... | |
virtual bool | setPidErrorLimits (const PidControlTypeEnum &pidtype, const double *limits)=0 |
Get the error limit for the controller on all joints. More... | |
virtual bool | getPidError (const PidControlTypeEnum &pidtype, int j, double *err)=0 |
Get the current error for a joint. More... | |
virtual bool | getPidErrors (const PidControlTypeEnum &pidtype, double *errs)=0 |
Get the error of all joints. More... | |
virtual bool | getPidOutput (const PidControlTypeEnum &pidtype, int j, double *out)=0 |
Get the output of the controller (e.g. More... | |
virtual bool | getPidOutputs (const PidControlTypeEnum &pidtype, double *outs)=0 |
Get the output of the controllers (e.g. More... | |
virtual bool | getPid (const PidControlTypeEnum &pidtype, int j, Pid *pid)=0 |
Get current pid value for a specific joint. More... | |
virtual bool | getPids (const PidControlTypeEnum &pidtype, Pid *pids)=0 |
Get current pid value for a specific joint. More... | |
virtual bool | getPidReference (const PidControlTypeEnum &pidtype, int j, double *ref)=0 |
Get the current reference of the pid controller for a specific joint. More... | |
virtual bool | getPidReferences (const PidControlTypeEnum &pidtype, double *refs)=0 |
Get the current reference of all pid controllers. More... | |
virtual bool | getPidErrorLimit (const PidControlTypeEnum &pidtype, int j, double *limit)=0 |
Get the error limit for the controller on a specific joint. More... | |
virtual bool | getPidErrorLimits (const PidControlTypeEnum &pidtype, double *limits)=0 |
Get the error limit for all controllers. More... | |
virtual bool | resetPid (const PidControlTypeEnum &pidtype, int j)=0 |
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... | |
virtual bool | disablePid (const PidControlTypeEnum &pidtype, int j)=0 |
Disable the pid computation for a joint. More... | |
virtual bool | enablePid (const PidControlTypeEnum &pidtype, int j)=0 |
Enable the pid computation for a joint. More... | |
virtual bool | setPidOffset (const PidControlTypeEnum &pidtype, int j, double v)=0 |
Set offset value for a given controller. More... | |
virtual bool | isPidEnabled (const PidControlTypeEnum &pidtype, int j, bool *enabled)=0 |
Get the current status (enabled/disabled) of the pid. More... | |
![]() | |
virtual | ~IPositionControl () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | positionMove (int j, double ref)=0 |
Set new reference point for a single axis. More... | |
virtual bool | positionMove (const double *refs)=0 |
Set new reference point for all axes. More... | |
virtual bool | relativeMove (int j, double delta)=0 |
Set relative position. More... | |
virtual bool | relativeMove (const double *deltas)=0 |
Set relative position, all joints. More... | |
virtual bool | checkMotionDone (int j, bool *flag)=0 |
Check if the current trajectory is terminated. More... | |
virtual bool | checkMotionDone (bool *flag)=0 |
Check if the current trajectory is terminated. More... | |
virtual bool | setRefSpeed (int j, double sp)=0 |
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory. More... | |
virtual bool | setRefSpeeds (const double *spds)=0 |
Set reference speed on all joints. More... | |
virtual bool | setRefAcceleration (int j, double acc)=0 |
Set reference acceleration for a joint. More... | |
virtual bool | setRefAccelerations (const double *accs)=0 |
Set reference acceleration on all joints. More... | |
virtual bool | getRefSpeed (int j, double *ref)=0 |
Get reference speed for a joint. More... | |
virtual bool | getRefSpeeds (double *spds)=0 |
Get reference speed of all joints. More... | |
virtual bool | getRefAcceleration (int j, double *acc)=0 |
Get reference acceleration for a joint. More... | |
virtual bool | getRefAccelerations (double *accs)=0 |
Get reference acceleration of all joints. More... | |
virtual bool | stop (int j)=0 |
Stop motion, single joint. More... | |
virtual bool | stop ()=0 |
Stop motion, multiple joints. More... | |
virtual bool | positionMove (const int n_joint, const int *joints, const double *refs)=0 |
Set new reference point for a subset of joints. More... | |
virtual bool | relativeMove (const int n_joint, const int *joints, const double *deltas)=0 |
Set relative position for a subset of joints. More... | |
virtual bool | checkMotionDone (const int n_joint, const int *joints, bool *flag)=0 |
Check if the current trajectory is terminated. More... | |
virtual bool | setRefSpeeds (const int n_joint, const int *joints, const double *spds)=0 |
Set reference speed on all joints. More... | |
virtual bool | setRefAccelerations (const int n_joint, const int *joints, const double *accs)=0 |
Set reference acceleration on all joints. More... | |
virtual bool | getRefSpeeds (const int n_joint, const int *joints, double *spds)=0 |
Get reference speed of all joints. More... | |
virtual bool | getRefAccelerations (const int n_joint, const int *joints, double *accs)=0 |
Get reference acceleration for a joint. More... | |
virtual bool | stop (const int n_joint, const int *joints)=0 |
Stop motion for subset of joints. More... | |
virtual bool | getTargetPosition (const int joint, double *ref) |
Get the last position reference for the specified axis. More... | |
virtual bool | getTargetPositions (double *refs) |
Get the last position reference for all axes. More... | |
virtual bool | getTargetPositions (const int n_joint, const int *joints, double *refs) |
Get the last position reference for the specified group of axes. More... | |
![]() | |
virtual | ~IPositionDirect () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | setPosition (int j, double ref)=0 |
Set new position for a single axis. More... | |
virtual bool | setPositions (const int n_joint, const int *joints, const double *refs)=0 |
Set new reference point for all axes. More... | |
virtual bool | setPositions (const double *refs)=0 |
Set new position for a set of axis. More... | |
virtual bool | getRefPosition (const int joint, double *ref) |
Get the last position reference for the specified axis. More... | |
virtual bool | getRefPositions (double *refs) |
Get the last position reference for all axes. More... | |
virtual bool | getRefPositions (const int n_joint, const int *joints, double *refs) |
Get the last position reference for the specified group of axes. More... | |
![]() | |
virtual | ~IVelocityControl () |
Destructor. More... | |
virtual bool | getAxes (int *axes)=0 |
Get the number of controlled axes. More... | |
virtual bool | velocityMove (int j, double sp)=0 |
Start motion at a given speed, single joint. More... | |
virtual bool | velocityMove (const double *sp)=0 |
Start motion at a given speed, multiple joints. More... | |
virtual bool | setRefAcceleration (int j, double acc)=0 |
Set reference acceleration for a joint. More... | |
virtual bool | setRefAccelerations (const double *accs)=0 |
Set reference acceleration on all joints. More... | |
virtual bool | getRefAcceleration (int j, double *acc)=0 |
Get reference acceleration for a joint. More... | |
virtual bool | getRefAccelerations (double *accs)=0 |
Get reference acceleration of all joints. More... | |
virtual bool | stop (int j)=0 |
Stop motion, single joint. More... | |
virtual bool | stop ()=0 |
Stop motion, multiple joints. More... | |
virtual bool | velocityMove (const int n_joint, const int *joints, const double *spds)=0 |
Start motion at a given speed for a subset of joints. More... | |
virtual bool | getRefVelocity (const int joint, double *vel) |
Get the last reference speed set by velocityMove for single joint. More... | |
virtual bool | getRefVelocities (double *vels) |
Get the last reference speed set by velocityMove for all joints. More... | |
virtual bool | getRefVelocities (const int n_joint, const int *joints, double *vels) |
Get the last reference speed set by velocityMove for a group of joints. More... | |
virtual bool | setRefAccelerations (const int n_joint, const int *joints, const double *accs)=0 |
Set reference acceleration for a subset of joints. More... | |
virtual bool | getRefAccelerations (const int n_joint, const int *joints, double *accs)=0 |
Get reference acceleration for a subset of joints. More... | |
virtual bool | stop (const int n_joint, const int *joints)=0 |
Stop motion for a subset of joints. More... | |
![]() | |
virtual | ~IPWMControl () |
virtual bool | getNumberOfMotors (int *number)=0 |
Retrieves the number of controlled motors from the current physical interface. More... | |
virtual bool | setRefDutyCycle (int m, double ref)=0 |
Sets the reference dutycycle to a single motor. More... | |
virtual bool | setRefDutyCycles (const double *refs)=0 |
Sets the reference dutycycle for all the motors. More... | |
virtual bool | getRefDutyCycle (int m, double *ref)=0 |
Gets the last reference sent using the setRefDutyCycle function. More... | |
virtual bool | getRefDutyCycles (double *refs)=0 |
Gets the last reference sent using the setRefDutyCycles function. More... | |
virtual bool | getDutyCycle (int m, double *val)=0 |
Gets the current dutycycle of the output of the amplifier (i.e. More... | |
virtual bool | getDutyCycles (double *vals)=0 |
Gets the current dutycycle of the output of the amplifier (i.e. More... | |
![]() | |
virtual | ~ICurrentControl () |
Destructor. More... | |
virtual bool | getNumberOfMotors (int *ax)=0 |
Retrieves the number of controlled axes from the current physical interface. More... | |
virtual bool | getCurrent (int m, double *curr)=0 |
Get the instantaneous current measurement for a single motor. More... | |
virtual bool | getCurrents (double *currs)=0 |
Get the instantaneous current measurement for all motors. More... | |
virtual bool | getCurrentRange (int m, double *min, double *max)=0 |
Get the full scale of the current measurement for a given motor (e.g. More... | |
virtual bool | getCurrentRanges (double *min, double *max)=0 |
Get the full scale of the current measurements for all motors motor (e.g. More... | |
virtual bool | setRefCurrents (const double *currs)=0 |
Set the reference value of the currents for all motors. More... | |
virtual bool | setRefCurrent (int m, double curr)=0 |
Set the reference value of the current for a single motor. More... | |
virtual bool | setRefCurrents (const int n_motor, const int *motors, const double *currs)=0 |
Set the reference value of the current for a group of motors. More... | |
virtual bool | getRefCurrents (double *currs)=0 |
Get the reference value of the currents for all motors. More... | |
virtual bool | getRefCurrent (int m, double *curr)=0 |
Get the reference value of the current for a single motor. More... | |
![]() | |
virtual | ~IEncodersTimed () |
Destructor. More... | |
virtual bool | getEncodersTimed (double *encs, double *time)=0 |
Read the instantaneous acceleration of all axes. More... | |
virtual bool | getEncoderTimed (int j, double *encs, double *time)=0 |
Read the instantaneous acceleration of all axes. More... | |
![]() | |
virtual | ~IEncoders () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | resetEncoder (int j)=0 |
Reset encoder, single joint. More... | |
virtual bool | resetEncoders ()=0 |
Reset encoders. More... | |
virtual bool | setEncoder (int j, double val)=0 |
Set the value of the encoder for a given joint. More... | |
virtual bool | setEncoders (const double *vals)=0 |
Set the value of all encoders. More... | |
virtual bool | getEncoder (int j, double *v)=0 |
Read the value of an encoder. More... | |
virtual bool | getEncoders (double *encs)=0 |
Read the position of all axes. More... | |
virtual bool | getEncoderSpeed (int j, double *sp)=0 |
Read the istantaneous speed of an axis. More... | |
virtual bool | getEncoderSpeeds (double *spds)=0 |
Read the instantaneous speed of all axes. More... | |
virtual bool | getEncoderAcceleration (int j, double *spds)=0 |
Read the instantaneous acceleration of an axis. More... | |
virtual bool | getEncoderAccelerations (double *accs)=0 |
Read the instantaneous acceleration of all axes. More... | |
![]() | |
virtual | ~IMotor () |
Destructor. More... | |
virtual bool | getNumberOfMotors (int *num)=0 |
Get the number of available motors. More... | |
virtual bool | getTemperature (int m, double *val)=0 |
Get temperature of a motor. More... | |
virtual bool | getTemperatures (double *vals)=0 |
Get temperature of all the motors. More... | |
virtual bool | getTemperatureLimit (int m, double *temp)=0 |
Retreives the current temperature limit for a specific motor. More... | |
virtual bool | setTemperatureLimit (int m, const double temp)=0 |
Set the temperature limit for a specific motor. More... | |
virtual bool | getGearboxRatio (int m, double *val) |
Get the gearbox ratio for a specific motor. More... | |
virtual bool | setGearboxRatio (int m, const double val) |
Set the gearbox ratio for a specific motor. More... | |
![]() | |
virtual | ~IMotorEncoders () |
Destructor. More... | |
virtual bool | getNumberOfMotorEncoders (int *num)=0 |
Get the number of available motor encoders. More... | |
virtual bool | resetMotorEncoder (int m)=0 |
Reset motor encoder, single motor. More... | |
virtual bool | resetMotorEncoders ()=0 |
Reset motor encoders. More... | |
virtual bool | setMotorEncoderCountsPerRevolution (int m, const double cpr)=0 |
Sets number of counts per revolution for motor encoder m. More... | |
virtual bool | getMotorEncoderCountsPerRevolution (int m, double *cpr)=0 |
Gets number of counts per revolution for motor encoder m. More... | |
virtual bool | setMotorEncoder (int m, const double val)=0 |
Set the value of the motor encoder for a given motor. More... | |
virtual bool | setMotorEncoders (const double *vals)=0 |
Set the value of all motor encoders. More... | |
virtual bool | getMotorEncoder (int m, double *v)=0 |
Read the value of a motor encoder. More... | |
virtual bool | getMotorEncoders (double *encs)=0 |
Read the position of all motor encoders. More... | |
virtual bool | getMotorEncodersTimed (double *encs, double *time)=0 |
Read the instantaneous position of all motor encoders. More... | |
virtual bool | getMotorEncoderTimed (int m, double *encs, double *time)=0 |
Read the instantaneous position of a motor encoder. More... | |
virtual bool | getMotorEncoderSpeed (int m, double *sp)=0 |
Read the istantaneous speed of a motor encoder. More... | |
virtual bool | getMotorEncoderSpeeds (double *spds)=0 |
Read the instantaneous speed of all motor encoders. More... | |
virtual bool | getMotorEncoderAcceleration (int m, double *acc)=0 |
Read the instantaneous acceleration of a motor encoder. More... | |
virtual bool | getMotorEncoderAccelerations (double *accs)=0 |
Read the instantaneous acceleration of all motor encoders. More... | |
![]() | |
virtual | ~IAmplifierControl () |
Destructor. More... | |
virtual bool | enableAmp (int j)=0 |
Enable the amplifier on a specific joint. More... | |
virtual bool | disableAmp (int j)=0 |
Disable the amplifier on a specific joint. More... | |
virtual bool | getAmpStatus (int *st)=0 |
virtual bool | getAmpStatus (int j, int *v)=0 |
virtual bool | getCurrents (double *vals)=0 |
virtual bool | getCurrent (int j, double *val)=0 |
virtual bool | getMaxCurrent (int j, double *v)=0 |
Returns the maximum electric current allowed for a given motor. More... | |
virtual bool | setMaxCurrent (int j, double v)=0 |
virtual bool | getNominalCurrent (int m, double *val) |
virtual bool | setNominalCurrent (int m, const double val) |
virtual bool | getPeakCurrent (int m, double *val) |
virtual bool | setPeakCurrent (int m, const double val) |
virtual bool | getPWM (int j, double *val) |
virtual bool | getPWMLimit (int j, double *val) |
virtual bool | setPWMLimit (int j, const double val) |
virtual bool | getPowerSupplyVoltage (int j, double *val) |
![]() | |
virtual | ~IControlLimits () |
Destructor. More... | |
virtual bool | setLimits (int axis, double min, double max)=0 |
Set the software limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation. More... | |
virtual bool | getLimits (int axis, double *min, double *max)=0 |
Get the software limits for a particular axis. More... | |
virtual bool | setVelLimits (int axis, double min, double max)=0 |
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... | |
virtual bool | getVelLimits (int axis, double *min, double *max)=0 |
Get the software speed limits for a particular axis. 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 yarp::dev::IRemoteCalibrator * | getCalibratorDevice () |
getCalibratorDevice: return the pointer stored with the setCalibratorDevice More... | |
virtual bool | isCalibratorDevicePresent (bool *isCalib) |
isCalibratorDevicePresent: check if a calibrator device has been set More... | |
virtual void | releaseCalibratorDevice () |
releaseCalibratorDevice: reset the internal pointer to NULL when stop using the calibrator More... | |
virtual bool | calibrateSingleJoint (int j)=0 |
calibrateSingleJoint: call the calibration procedure for the single joint More... | |
virtual bool | calibrateWholePart ()=0 |
calibrateWholePart: call the procedure for calibrating the whole device More... | |
virtual bool | homingSingleJoint (int j)=0 |
homingSingleJoint: call the homing procedure for a single joint More... | |
virtual bool | homingWholePart ()=0 |
homingWholePart: call the homing procedure for a the whole part/device More... | |
virtual bool | parkSingleJoint (int j, bool _wait=true)=0 |
parkSingleJoint(): start the parking procedure for the single joint More... | |
virtual bool | parkWholePart ()=0 |
parkWholePart: start the parking procedure for the whole part More... | |
virtual bool | quitCalibrate ()=0 |
quitCalibrate: interrupt the calibration procedure More... | |
virtual bool | quitPark ()=0 |
quitPark: interrupt the park procedure More... | |
![]() | |
IControlCalibration () | |
virtual | ~IControlCalibration () |
Destructor. More... | |
virtual bool | calibrateAxisWithParams (int axis, unsigned int type, double p1, double p2, double p3)=0 |
Start calibration, this method is very often platform specific. More... | |
virtual bool | setCalibrationParameters (int axis, const CalibrationParameters ¶ms) |
Start calibration, this method is very often platform specific. More... | |
virtual bool | calibrationDone (int j)=0 |
Check if the calibration is terminated, on a particular joint. 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 bool | abortCalibration () |
virtual bool | abortPark () |
![]() | |
virtual | ~ITorqueControl () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | getRefTorques (double *t)=0 |
Get the reference value of the torque for all joints. More... | |
virtual bool | getRefTorque (int j, double *t)=0 |
Get the reference value of the torque for a given joint. More... | |
virtual bool | setRefTorques (const double *t)=0 |
Set the reference value of the torque for all joints. More... | |
virtual bool | setRefTorque (int j, double t)=0 |
Set the reference value of the torque for a given joint. More... | |
virtual bool | setRefTorques (const int n_joint, const int *joints, const double *t) |
Set new torque reference for a subset of joints. More... | |
virtual bool | getMotorTorqueParams (int j, yarp::dev::MotorTorqueParameters *params) |
Get a subset of motor parameters (bemf, ktau etc) useful for torque control. More... | |
virtual bool | setMotorTorqueParams (int j, const yarp::dev::MotorTorqueParameters params) |
Set a subset of motor parameters (bemf, ktau etc) useful for torque control. More... | |
virtual bool | getTorque (int j, double *t)=0 |
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor). More... | |
virtual bool | getTorques (double *t)=0 |
Get the value of the torque for all joints (this is the feedback if you have torque sensors). More... | |
virtual bool | getTorqueRange (int j, double *min, double *max)=0 |
Get the full scale of the torque sensor of a given joint. More... | |
virtual bool | getTorqueRanges (double *min, double *max)=0 |
Get the full scale of the torque sensors of all joints. More... | |
![]() | |
virtual | ~IImpedanceControl () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | getImpedance (int j, double *stiffness, double *damping)=0 |
Get current impedance gains (stiffness,damping,offset) for a specific joint. More... | |
virtual bool | setImpedance (int j, double stiffness, double damping)=0 |
Set current impedance gains (stiffness,damping) for a specific joint. More... | |
virtual bool | setImpedanceOffset (int j, double offset)=0 |
Set current force Offset for a specific joint. More... | |
virtual bool | getImpedanceOffset (int j, double *offset)=0 |
Get current force Offset for a specific joint. More... | |
virtual bool | getCurrentImpedanceLimit (int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp)=0 |
Get the current impedandance limits for a specific joint. More... | |
![]() | |
virtual | ~IControlMode () |
virtual bool | getControlMode (int j, int *mode)=0 |
Get the current control mode. More... | |
virtual bool | getControlModes (int *modes)=0 |
Get the current control mode (multiple joints). More... | |
virtual bool | getControlModes (const int n_joint, const int *joints, int *modes)=0 |
Get the current control mode for a subset of axes. More... | |
virtual bool | setControlMode (const int j, const int mode)=0 |
Set the current control mode. More... | |
virtual bool | setControlModes (const int n_joint, const int *joints, int *modes)=0 |
Set the current control mode for a subset of axes. More... | |
virtual bool | setControlModes (int *modes)=0 |
Set the current control mode (multiple joints). More... | |
![]() | |
virtual | ~IMultipleWrapper () |
Destructor. More... | |
virtual bool | attachAll (const PolyDriverList &drivers)=0 |
Attach to a list of objects. More... | |
virtual bool | detachAll ()=0 |
Detach the object (you must have first called attach). More... | |
![]() | |
virtual | ~IAxisInfo () |
Destructor. More... | |
virtual bool | getAxes (int *ax)=0 |
Get the number of controlled axes. More... | |
virtual bool | getAxisName (int axis, std::string &name)=0 |
virtual bool | getJointType (int axis, yarp::dev::JointTypeEnum &type) |
![]() | |
virtual | ~IPreciselyTimed () |
virtual yarp::os::Stamp | getLastInputStamp ()=0 |
Return the time stamp relative to the last acquisition. More... | |
![]() | |
virtual | ~IInteractionMode () |
Destructor. More... | |
virtual bool | getInteractionMode (int axis, yarp::dev::InteractionModeEnum *mode)=0 |
Get the current interaction mode of the robot, values can be stiff or compliant. More... | |
virtual bool | getInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes)=0 |
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant. More... | |
virtual bool | getInteractionModes (yarp::dev::InteractionModeEnum *modes)=0 |
Get the current interaction mode of the robot for a all the joints, values can be stiff or compliant. More... | |
virtual bool | setInteractionMode (int axis, yarp::dev::InteractionModeEnum mode)=0 |
Set the interaction mode of the robot, values can be stiff or compliant. More... | |
virtual bool | setInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes)=0 |
Set the interaction mode of the robot for a set of joints, values can be stiff or compliant. More... | |
virtual bool | setInteractionModes (yarp::dev::InteractionModeEnum *modes)=0 |
Set the interaction mode of the robot for a all the joints, values can be stiff or compliant. More... | |
![]() | |
virtual | ~IRemoteVariables () |
Destructor. More... | |
virtual bool | getRemoteVariable (std::string key, yarp::os::Bottle &val)=0 |
virtual bool | setRemoteVariable (std::string key, const yarp::os::Bottle &val)=0 |
virtual bool | getRemoteVariablesList (yarp::os::Bottle *listOfKeys)=0 |
![]() | |
virtual | ~IJointFault () |
virtual bool | getLastJointFault (int j, int &fault, std::string &message)=0 |
controlboardremapper
: device that takes a list of axes from multiple controlboards and expose them as a single controlboard.
YARP device name |
---|
controlboardremapper |
Parameters required by this device are:
Parameter name | SubParameter | Type | Units | Default Value | Required | Description | Notes |
---|---|---|---|---|---|---|---|
axesNames | - | vector of strings | - | - | Yes | Ordered list of the axes that are part of the remapped device. |
The axes are then mapped to the wrapped controlboard in the attachAll method, using the values returned by the getAxisName method of the controlboard. If different axes in two attached controlboard have the same name, the behaviour of this device is undefined.
Configuration file using .ini format.
For compatibility with the controlBoard_nws_yarp, the networks keyword can also be used to select the desired joints. For more information on the syntax of the networks, see the controlBoard_nws_yarp class.
Definition at line 69 of file ControlBoardRemapper.h.
|
default |
|
delete |
|
delete |
|
overridedefault |
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3165 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3159 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Attach to a list of objects.
drivers | the polydriver list that you want to attach to. |
Implements yarp::dev::IMultipleWrapper.
Definition at line 232 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Implements yarp::dev::IControlCalibration.
Definition at line 3110 of file ControlBoardRemapper.cpp.
|
overridevirtual |
calibrateSingleJoint: call the calibration procedure for the single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2912 of file ControlBoardRemapper.cpp.
|
overridevirtual |
calibrateWholePart: call the procedure for calibrating the whole device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2938 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Check if the calibration is terminated, on a particular joint.
Non blocking.
Implements yarp::dev::IControlCalibration.
Definition at line 3139 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
flag | is a pointer to return value ("and" of all joints) |
Implements yarp::dev::IPositionControl.
Definition at line 1211 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
joints | pointer to the array of joint numbers |
flag | pointer to return value (logical "and" of all set of joints) |
Implements yarp::dev::IPositionControl.
Definition at line 1243 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Check if the current trajectory is terminated.
Non blocking.
j | is the axis number |
flag | is a pointer to return value |
Implements yarp::dev::IPositionControl.
Definition at line 1191 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Close the device driver by deallocating all resources and closing ports.
Reimplemented from yarp::dev::DeviceDriver.
Reimplemented in RemoteControlBoardRemapper.
Definition at line 23 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Detach the object (you must have first called attach).
Implements yarp::dev::IMultipleWrapper.
Definition at line 462 of file ControlBoardRemapper.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 2564 of file ControlBoardRemapper.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 924 of file ControlBoardRemapper.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 2544 of file ControlBoardRemapper.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 939 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 2569 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 2599 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the number of controlled axes.
This command asks the number of controlled axes for the current physical interface.
ax | storage to return param |
Implements yarp::dev::IAxisInfo.
Definition at line 980 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAxisInfo.
Definition at line 3173 of file ControlBoardRemapper.cpp.
|
overridevirtual |
getCalibratorDevice: return the pointer stored with the setCalibratorDevice
Reimplemented from yarp::dev::IRemoteCalibrator.
Definition at line 2902 of file ControlBoardRemapper.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 3568 of file ControlBoardRemapper.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 3613 of file ControlBoardRemapper.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 3582 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 4280 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the current impedandance limits for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3548 of file ControlBoardRemapper.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 4327 of file ControlBoardRemapper.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 4344 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 4297 of file ControlBoardRemapper.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 4233 of file ControlBoardRemapper.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 4250 of file ControlBoardRemapper.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 1786 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of an axis.
j | axis number |
spds | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 1933 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of all axes.
accs | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 1953 of file ControlBoardRemapper.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 1806 of file ControlBoardRemapper.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 1884 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous speed of all axes.
spds | pointer to storage for the output values |
Implements yarp::dev::IEncoders.
Definition at line 1904 of file ControlBoardRemapper.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 1835 of file ControlBoardRemapper.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 1864 of file ControlBoardRemapper.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 2075 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get current impedance gains (stiffness,damping,offset) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3508 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3528 of file ControlBoardRemapper.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 3996 of file ControlBoardRemapper.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 4016 of file ControlBoardRemapper.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 4049 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAxisInfo.
Definition at line 3193 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Return the time stamp relative to the last acquisition.
Implements yarp::dev::IPreciselyTimed.
Definition at line 3765 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IJointFault.
Definition at line 1627 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the software limits for a particular axis.
axis | joint number |
pointer | to store the value of the lower limit |
pointer | to store the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 2841 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Returns the maximum electric current allowed for a given motor.
Exceeding this value will trigger instantaneous hardware fault.
j | motor number |
v | the return value |
Implements yarp::dev::IAmplifierControl.
Definition at line 2639 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the value of a motor encoder.
m | motor encoder number |
v | pointer to storage for the return value |
Implements yarp::dev::IMotorEncoders.
Definition at line 2344 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of a motor encoder.
m | motor number |
acc | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 2486 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous acceleration of all motor encoders.
accs | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 2506 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Gets number of counts per revolution for motor encoder m.
m | motor number |
cpr | vals pointer to the new value |
Implements yarp::dev::IMotorEncoders.
Definition at line 2324 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the position of all motor encoders.
encs | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 2364 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the istantaneous speed of a motor encoder.
m | motor number |
sp | pointer to storage for the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 2437 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Read the instantaneous speed of all motor encoders.
spds | pointer to storage for the output values |
Implements yarp::dev::IMotorEncoders.
Definition at line 2457 of file ControlBoardRemapper.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 2388 of file ControlBoardRemapper.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 2417 of file ControlBoardRemapper.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 3329 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2659 of file ControlBoardRemapper.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 2537 of file ControlBoardRemapper.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 1983 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2679 of file ControlBoardRemapper.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 759 of file ControlBoardRemapper.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 645 of file ControlBoardRemapper.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 855 of file ControlBoardRemapper.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 874 of file ControlBoardRemapper.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 665 of file ControlBoardRemapper.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 693 of file ControlBoardRemapper.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 712 of file ControlBoardRemapper.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 807 of file ControlBoardRemapper.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 826 of file ControlBoardRemapper.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 778 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2798 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2739 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2758 of file ControlBoardRemapper.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 1482 of file ControlBoardRemapper.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 1532 of file ControlBoardRemapper.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 1502 of file ControlBoardRemapper.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 4437 of file ControlBoardRemapper.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 4454 of file ControlBoardRemapper.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 4186 of file ControlBoardRemapper.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 4203 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the last position reference for the specified axis.
This is the dual of setPositionsRaw 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 3803 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the last position reference for the specified group of axes.
This is the dual of setPositionsRaw 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 3855 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the last position reference for all axes.
This is the dual of setPositionsRaw 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 3824 of file ControlBoardRemapper.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 1398 of file ControlBoardRemapper.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 1449 of file ControlBoardRemapper.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 1418 of file ControlBoardRemapper.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 3242 of file ControlBoardRemapper.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 3213 of file ControlBoardRemapper.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 3963 of file ControlBoardRemapper.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 3933 of file ControlBoardRemapper.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 3911 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2116 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2183 of file ControlBoardRemapper.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 1046 of file ControlBoardRemapper.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 1098 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the last position reference for all 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 1067 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get temperature of a motor.
m | motor number |
val | retrieved motor temperature |
Implements yarp::dev::IMotor.
Definition at line 1989 of file ControlBoardRemapper.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 2035 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get temperature of all the motors.
vals | pointer to an array containing all motor temperatures |
Implements yarp::dev::IMotor.
Definition at line 2009 of file ControlBoardRemapper.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 3409 of file ControlBoardRemapper.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 3459 of file ControlBoardRemapper.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 3479 of file ControlBoardRemapper.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 3429 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Get the software speed limits for a particular axis.
axis | 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 2881 of file ControlBoardRemapper.cpp.
|
overridevirtual |
homingSingleJoint: call the homing procedure for a single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2964 of file ControlBoardRemapper.cpp.
|
overridevirtual |
homingWholePart: call the homing procedure for a the whole part/device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2990 of file ControlBoardRemapper.cpp.
|
overridevirtual |
isCalibratorDevicePresent: check if a calibrator device has been set
Reimplemented from yarp::dev::IRemoteCalibrator.
Definition at line 2907 of file ControlBoardRemapper.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 959 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Open the device driver.
prop | is a Searchable object which contains the parameters. Allowed parameters are described in the class documentation. |
Reimplemented from yarp::dev::DeviceDriver.
Reimplemented in RemoteControlBoardRemapper.
Definition at line 28 of file ControlBoardRemapper.cpp.
|
delete |
|
delete |
|
overridevirtual |
parkSingleJoint(): start the parking procedure for the single joint
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3009 of file ControlBoardRemapper.cpp.
|
overridevirtual |
parkWholePart: start the parking procedure for the whole part
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3035 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set new reference point for all axes.
refs | array, new reference points. |
Implements yarp::dev::IPositionControl.
Definition at line 1006 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set new reference point for a subset of joints.
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 1026 of file ControlBoardRemapper.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 986 of file ControlBoardRemapper.cpp.
|
overridevirtual |
quitCalibrate: interrupt the calibration procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3056 of file ControlBoardRemapper.cpp.
|
overridevirtual |
quitPark: interrupt the park procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 3082 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set relative position, all joints.
deltas | pointer to the relative commands |
Implements yarp::dev::IPositionControl.
Definition at line 1151 of file ControlBoardRemapper.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 1171 of file ControlBoardRemapper.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 1131 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reset encoder, single joint.
Set the encoder value to zero
j | encoder number |
Implements yarp::dev::IEncoders.
Definition at line 1690 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reset encoders.
Set the encoders value to zero
Implements yarp::dev::IEncoders.
Definition at line 1709 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reset motor encoder, single motor.
Set the encoder value to zero.
m | motor number |
Implements yarp::dev::IMotorEncoders.
Definition at line 2205 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reset motor encoders.
Set the motor encoders value to zero.
Implements yarp::dev::IMotorEncoders.
Definition at line 2225 of file ControlBoardRemapper.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 904 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 3124 of file ControlBoardRemapper.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 3646 of file ControlBoardRemapper.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 3665 of file ControlBoardRemapper.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 3685 of file ControlBoardRemapper.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 1737 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set the value of all encoders.
vals | pointer to the new values |
Implements yarp::dev::IEncoders.
Definition at line 1757 of file ControlBoardRemapper.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 2095 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set current impedance gains (stiffness,damping) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3369 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 3389 of file ControlBoardRemapper.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 4079 of file ControlBoardRemapper.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 4099 of file ControlBoardRemapper.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 4119 of file ControlBoardRemapper.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.
axis | 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 2821 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IAmplifierControl.
Definition at line 2619 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set the value of the motor encoder for a given motor.
m | motor number |
val | new value |
Implements yarp::dev::IMotorEncoders.
Definition at line 2254 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Sets number of counts per revolution for motor encoder m.
m | motor number |
cpr | new value |
Implements yarp::dev::IMotorEncoders.
Definition at line 2304 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set the value of all motor encoders.
vals | pointer to the new values |
Implements yarp::dev::IMotorEncoders.
Definition at line 2274 of file ControlBoardRemapper.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 3349 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2719 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2699 of file ControlBoardRemapper.cpp.
|
overridevirtual |
ControlBoard methods.
Implements yarp::dev::IPidControl.
Definition at line 500 of file ControlBoardRemapper.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 597 of file ControlBoardRemapper.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 616 of file ControlBoardRemapper.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 740 of file ControlBoardRemapper.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 548 of file ControlBoardRemapper.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 568 of file ControlBoardRemapper.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 519 of file ControlBoardRemapper.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 3705 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set new position for a set of axis.
refs | specifies the new reference points |
Implements yarp::dev::IPositionDirect.
Definition at line 3745 of file ControlBoardRemapper.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 3725 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 2778 of file ControlBoardRemapper.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 1338 of file ControlBoardRemapper.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 1358 of file ControlBoardRemapper.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 1378 of file ControlBoardRemapper.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 4374 of file ControlBoardRemapper.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 4417 of file ControlBoardRemapper.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 4391 of file ControlBoardRemapper.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 4139 of file ControlBoardRemapper.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 4156 of file ControlBoardRemapper.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 1278 of file ControlBoardRemapper.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 1298 of file ControlBoardRemapper.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 1318 of file ControlBoardRemapper.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 3291 of file ControlBoardRemapper.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 3261 of file ControlBoardRemapper.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 3309 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 2150 of file ControlBoardRemapper.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 2055 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Set the software speed limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation.
axis | joint number |
min | the value of the lower limit |
max | the value of the upper limit |
Implements yarp::dev::IControlLimits.
Definition at line 2861 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Stop motion, multiple joints.
Implements yarp::dev::IPositionControl.
Definition at line 1585 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Stop motion for subset of joints.
joints | pointer to the array of joint numbers |
Implements yarp::dev::IPositionControl.
Definition at line 1605 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Stop motion, single joint.
j | joint number |
Implements yarp::dev::IPositionControl.
Definition at line 1565 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Start motion at a given speed, multiple joints.
sp | pointer to the array containing the new speed values |
Implements yarp::dev::IVelocityControl.
Definition at line 1669 of file ControlBoardRemapper.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 3891 of file ControlBoardRemapper.cpp.
|
overridevirtual |
Start motion at a given speed, single joint.
j | joint number |
sp | speed value |
Implements yarp::dev::IVelocityControl.
Definition at line 1649 of file ControlBoardRemapper.cpp.
|
inline |
Return the value of the verbose flag.
Definition at line 186 of file ControlBoardRemapper.h.