remote_controlboard
: The client side of the control board, connects to a remote controlboard using the YARP network.
More...
#include <networkWrappers/RemoteControlBoard/RemoteControlBoard.h>
Public Member Functions | |
RemoteControlBoard ()=default | |
RemoteControlBoard (const RemoteControlBoard &)=delete | |
RemoteControlBoard (RemoteControlBoard &&)=delete | |
RemoteControlBoard & | operator= (const RemoteControlBoard &)=delete |
RemoteControlBoard & | operator= (RemoteControlBoard &&)=delete |
~RemoteControlBoard () override=default | |
bool | open (Searchable &config) override |
Open the DeviceDriver. | |
bool | close () override |
Close the device driver and stop the port connections. | |
bool | getAxes (int *ax) override |
Get the number of controlled axes. | |
bool | setPid (const PidControlTypeEnum &pidtype, int j, const Pid &pid) override |
Set new pid value for a joint axis. | |
bool | setPids (const PidControlTypeEnum &pidtype, const Pid *pids) override |
Set new pid value on multiple axes. | |
bool | setPidReference (const PidControlTypeEnum &pidtype, int j, double ref) override |
Set the controller reference for a given axis. | |
bool | setPidReferences (const PidControlTypeEnum &pidtype, const double *refs) override |
Set the controller reference, multiple axes. | |
bool | setPidErrorLimit (const PidControlTypeEnum &pidtype, int j, double limit) override |
Set the error limit for the controller on a specifi joint. | |
bool | setPidErrorLimits (const PidControlTypeEnum &pidtype, const double *limits) override |
Get the error limit for the controller on all joints. | |
bool | getPidError (const PidControlTypeEnum &pidtype, int j, double *err) override |
Get the current error for a joint. | |
bool | getPidErrors (const PidControlTypeEnum &pidtype, double *errs) override |
Get the error of all joints. | |
bool | getPid (const PidControlTypeEnum &pidtype, int j, Pid *pid) override |
Get current pid value for a specific joint. | |
bool | getPids (const PidControlTypeEnum &pidtype, Pid *pids) override |
Get current pid value for a specific joint. | |
bool | getPidReference (const PidControlTypeEnum &pidtype, int j, double *ref) override |
Get the current reference of the pid controller for a specific joint. | |
bool | getPidReferences (const PidControlTypeEnum &pidtype, double *refs) override |
Get the current reference of all pid controllers. | |
bool | getPidErrorLimit (const PidControlTypeEnum &pidtype, int j, double *limit) override |
Get the error limit for the controller on a specific joint. | |
bool | getPidErrorLimits (const PidControlTypeEnum &pidtype, double *limits) override |
Get the error limit for all controllers. | |
bool | resetPid (const PidControlTypeEnum &pidtype, int j) override |
Reset the controller of a given joint, usually sets the current status of the joint as the reference value for the PID, and resets the integrator. | |
bool | disablePid (const PidControlTypeEnum &pidtype, int j) override |
Disable the pid computation for a joint. | |
bool | enablePid (const PidControlTypeEnum &pidtype, int j) override |
Enable the pid computation for a joint. | |
bool | isPidEnabled (const PidControlTypeEnum &pidtype, int j, bool *enabled) override |
Get the current status (enabled/disabled) of the pid. | |
bool | getPidOutput (const PidControlTypeEnum &pidtype, int j, double *out) override |
Get the output of the controller (e.g. | |
bool | getPidOutputs (const PidControlTypeEnum &pidtype, double *outs) override |
Get the output of the controllers (e.g. | |
bool | setPidOffset (const PidControlTypeEnum &pidtype, int j, double v) override |
Set offset value for a given controller. | |
bool | resetEncoder (int j) override |
Reset encoder, single joint. | |
bool | resetEncoders () override |
Reset encoders. | |
bool | setEncoder (int j, double val) override |
Set the value of the encoder for a given joint. | |
bool | setEncoders (const double *vals) override |
Set the value of all encoders. | |
bool | getEncoder (int j, double *v) override |
Read the value of an encoder. | |
bool | getEncoderTimed (int j, double *v, double *t) override |
Read the instantaneous acceleration of all axes. | |
bool | getEncoders (double *encs) override |
Read the position of all axes. | |
bool | getEncodersTimed (double *encs, double *ts) override |
Read the instantaneous acceleration of all axes. | |
bool | getEncoderSpeed (int j, double *sp) override |
Read the istantaneous speed of an axis. | |
bool | getEncoderSpeeds (double *spds) override |
Read the instantaneous speed of all axes. | |
bool | getEncoderAcceleration (int j, double *acc) override |
Read the instantaneous acceleration of an axis. | |
bool | getEncoderAccelerations (double *accs) override |
Read the instantaneous acceleration of all axes. | |
bool | 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 | getNumberOfMotors (int *num) override |
Get the number of available motors. | |
bool | getTemperature (int m, double *val) override |
Get temperature of a motor. | |
bool | getTemperatures (double *vals) override |
Get temperature of all the motors. | |
bool | getTemperatureLimit (int m, double *val) override |
Retreives the current temperature limit for a specific motor. | |
bool | setTemperatureLimit (int m, const double val) override |
Set the temperature limit for a specific motor. | |
bool | getGearboxRatio (int m, double *val) override |
Get the gearbox ratio for a specific motor. | |
bool | setGearboxRatio (int m, const double val) override |
Set the gearbox ratio for a specific motor. | |
bool | resetMotorEncoder (int j) override |
Reset motor encoder, single motor. | |
bool | resetMotorEncoders () override |
Reset motor encoders. | |
bool | setMotorEncoder (int j, const double val) override |
Set the value of the motor encoder for a given motor. | |
bool | setMotorEncoderCountsPerRevolution (int m, const double cpr) override |
Sets number of counts per revolution for motor encoder m. | |
bool | getMotorEncoderCountsPerRevolution (int m, double *cpr) override |
Gets number of counts per revolution for motor encoder m. | |
bool | setMotorEncoders (const double *vals) override |
Set the value of all motor encoders. | |
bool | getMotorEncoder (int j, double *v) override |
Read the value of a motor encoder. | |
bool | getMotorEncoderTimed (int j, double *v, double *t) override |
Read the instantaneous position of a motor encoder. | |
bool | getMotorEncoders (double *encs) override |
Read the position of all motor encoders. | |
bool | getMotorEncodersTimed (double *encs, double *ts) override |
Read the instantaneous position of all motor encoders. | |
bool | getMotorEncoderSpeed (int j, double *sp) override |
Read the istantaneous speed of a motor encoder. | |
bool | getMotorEncoderSpeeds (double *spds) override |
Read the instantaneous speed of all motor encoders. | |
bool | getMotorEncoderAcceleration (int j, double *acc) override |
Read the instantaneous acceleration of a motor encoder. | |
bool | getMotorEncoderAccelerations (double *accs) override |
Read the instantaneous acceleration of all motor encoders. | |
bool | getNumberOfMotorEncoders (int *num) override |
Get the number of available motor encoders. | |
Stamp | getLastInputStamp () override |
Get the time stamp for the last read data. | |
bool | positionMove (int j, double ref) override |
Set new reference point for a single axis. | |
bool | positionMove (const int n_joint, const int *joints, const double *refs) override |
Set new reference point for a subset of joints. | |
bool | positionMove (const double *refs) override |
Set new reference point for all axes. | |
bool | getTargetPosition (const int joint, double *ref) override |
Get the last position reference for the specified axis. | |
bool | getTargetPositions (double *refs) override |
Get the last position reference for all axes. | |
bool | getTargetPositions (const int n_joint, const int *joints, double *refs) override |
Get the last position reference for the specified group of axes. | |
bool | relativeMove (int j, double delta) override |
Set relative position. | |
bool | relativeMove (const int n_joint, const int *joints, const double *refs) override |
Set relative position for a subset of joints. | |
bool | relativeMove (const double *deltas) override |
Set relative position, all joints. | |
bool | checkMotionDone (int j, bool *flag) override |
Check if the current trajectory is terminated. | |
bool | checkMotionDone (const int n_joint, const int *joints, bool *flag) override |
Check if the current trajectory is terminated. | |
bool | checkMotionDone (bool *flag) override |
Check if the current trajectory is terminated. | |
bool | setRefSpeed (int j, double sp) override |
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory. | |
bool | setRefSpeeds (const int n_joint, const int *joints, const double *spds) override |
Set reference speed on all joints. | |
bool | setRefSpeeds (const double *spds) override |
Set reference speed on all joints. | |
bool | setRefAcceleration (int j, double acc) override |
Set reference acceleration for a joint. | |
bool | setRefAccelerations (const int n_joint, const int *joints, const double *accs) override |
Set reference acceleration on all joints. | |
bool | setRefAccelerations (const double *accs) override |
Set reference acceleration on all joints. | |
bool | getRefSpeed (int j, double *ref) override |
Get reference speed for a joint. | |
bool | getRefSpeeds (const int n_joint, const int *joints, double *spds) override |
Get reference speed of all joints. | |
bool | getRefSpeeds (double *spds) override |
Get reference speed of all joints. | |
bool | getRefAcceleration (int j, double *acc) override |
Get reference acceleration for a joint. | |
bool | getRefAccelerations (const int n_joint, const int *joints, double *accs) override |
Get reference acceleration for a joint. | |
bool | getRefAccelerations (double *accs) override |
Get reference acceleration of all joints. | |
bool | stop (int j) override |
Stop motion, single joint. | |
bool | stop (const int len, const int *val1) override |
Stop motion for subset of joints. | |
bool | stop () override |
Stop motion, multiple joints. | |
bool | getLastJointFault (int j, int &fault, std::string &message) override |
bool | velocityMove (int j, double v) override |
Start motion at a given speed, single joint. | |
bool | velocityMove (const double *v) override |
Start motion at a given speed, multiple joints. | |
bool | enableAmp (int j) override |
Enable the amplifier on a specific joint. | |
bool | disableAmp (int j) override |
Disable the amplifier on a specific joint. | |
bool | getAmpStatus (int *st) override |
bool | getAmpStatus (int j, int *st) override |
bool | setMaxCurrent (int j, double v) override |
bool | getMaxCurrent (int j, double *v) override |
Returns the maximum electric current allowed for a given motor. | |
bool | getNominalCurrent (int m, double *val) override |
bool | setNominalCurrent (int m, const double val) override |
bool | getPeakCurrent (int m, double *val) override |
bool | setPeakCurrent (int m, const double val) override |
bool | getPWM (int m, double *val) override |
bool | getPWMLimit (int m, double *val) override |
bool | setPWMLimit (int m, const double val) override |
bool | getPowerSupplyVoltage (int m, double *val) override |
bool | setLimits (int axis, double min, double max) override |
Set the software limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation. | |
bool | getLimits (int axis, double *min, double *max) override |
Get the software limits for a particular axis. | |
bool | setVelLimits (int axis, double min, double max) override |
Set the software speed limits for a particular axis, the behavior of the control card when these limits are exceeded, depends on the implementation. | |
bool | getVelLimits (int axis, double *min, double *max) override |
Get the software speed limits for a particular axis. | |
bool | getAxisName (int j, std::string &name) override |
bool | getJointType (int j, yarp::dev::JointTypeEnum &type) override |
bool | calibrateRobot () override |
Calibrate robot by using an external calibrator. | |
bool | abortCalibration () override |
bool | abortPark () override |
bool | park (bool wait=true) override |
bool | calibrateAxisWithParams (int j, unsigned int ui, double v1, double v2, double v3) override |
Start calibration, this method is very often platform specific. | |
bool | setCalibrationParameters (int j, const CalibrationParameters ¶ms) override |
Start calibration, this method is very often platform specific. | |
bool | calibrationDone (int j) override |
Check if the calibration is terminated, on a particular joint. | |
bool | getRefTorque (int j, double *t) override |
Get the reference value of the torque for a given joint. | |
bool | getRefTorques (double *t) override |
Get the reference value of the torque for all joints. | |
bool | setRefTorques (const double *t) override |
Set the reference value of the torque for all joints. | |
bool | setRefTorque (int j, double v) override |
Set the reference value of the torque for a given joint. | |
bool | setRefTorques (const int n_joint, const int *joints, const double *t) override |
Set new torque reference for a subset of joints. | |
bool | setMotorTorqueParams (int j, const MotorTorqueParameters params) override |
Set a subset of motor parameters (bemf, ktau etc) useful for torque control. | |
bool | getMotorTorqueParams (int j, MotorTorqueParameters *params) override |
Get a subset of motor parameters (bemf, ktau etc) useful for torque control. | |
bool | getTorque (int j, double *t) override |
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor). | |
bool | getTorques (double *t) override |
Get the value of the torque for all joints (this is the feedback if you have torque sensors). | |
bool | getTorqueRange (int j, double *min, double *max) override |
Get the full scale of the torque sensor of a given joint. | |
bool | getTorqueRanges (double *min, double *max) override |
Get the full scale of the torque sensors of all joints. | |
bool | getImpedance (int j, double *stiffness, double *damping) override |
Get current impedance gains (stiffness,damping,offset) for a specific joint. | |
bool | getImpedanceOffset (int j, double *offset) override |
Get current force Offset for a specific joint. | |
bool | setImpedance (int j, double stiffness, double damping) override |
Set current impedance gains (stiffness,damping) for a specific joint. | |
bool | setImpedanceOffset (int j, double offset) override |
Set current force Offset for a specific joint. | |
bool | getCurrentImpedanceLimit (int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override |
Get the current impedandance limits for a specific joint. | |
bool | getControlMode (int j, int *mode) override |
Get the current control mode. | |
bool | getControlModes (int *modes) override |
Get the current control mode (multiple joints). | |
bool | getControlModes (const int n_joint, const int *joints, int *modes) override |
Get the current control mode for a subset of axes. | |
bool | setControlMode (const int j, const int mode) override |
Set the current control mode. | |
bool | setControlModes (const int n_joint, const int *joints, int *modes) override |
Set the current control mode for a subset of axes. | |
bool | setControlModes (int *modes) override |
Set the current control mode (multiple joints). | |
bool | setPosition (int j, double ref) override |
Set new position for a single axis. | |
bool | setPositions (const int n_joint, const int *joints, const double *refs) override |
Set new reference point for all axes. | |
bool | setPositions (const double *refs) override |
Set new position for a set of axis. | |
bool | getRefPosition (const int joint, double *ref) override |
Get the last position reference for the specified axis. | |
bool | getRefPositions (double *refs) override |
Get the last position reference for all axes. | |
bool | getRefPositions (const int n_joint, const int *joints, double *refs) override |
Get the last position reference for the specified group of axes. | |
bool | velocityMove (const int n_joint, const int *joints, const double *spds) override |
Start motion at a given speed for a subset of joints. | |
bool | getRefVelocity (const int joint, double *vel) override |
Get the last reference speed set by velocityMove for single joint. | |
bool | getRefVelocities (double *vels) override |
Get the last reference speed set by velocityMove for all joints. | |
bool | getRefVelocities (const int n_joint, const int *joints, double *vels) override |
Get the last reference speed set by velocityMove for a group of joints. | |
bool | getInteractionMode (int axis, yarp::dev::InteractionModeEnum *mode) override |
Get the current interaction mode of the robot, values can be stiff or compliant. | |
bool | getInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override |
Get the current interaction mode of the robot for a set of joints, values can be stiff or compliant. | |
bool | getInteractionModes (yarp::dev::InteractionModeEnum *modes) override |
Get the current interaction mode of the robot for a all the joints, values can be stiff or compliant. | |
bool | setInteractionMode (int axis, yarp::dev::InteractionModeEnum mode) override |
Set the interaction mode of the robot, values can be stiff or compliant. | |
bool | setInteractionModes (int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override |
Set the interaction mode of the robot for a set of joints, values can be stiff or compliant. | |
bool | setInteractionModes (yarp::dev::InteractionModeEnum *modes) override |
Set the interaction mode of the robot for a all the joints, values can be stiff or compliant. | |
bool | isCalibratorDevicePresent (bool *isCalib) override |
isCalibratorDevicePresent: check if a calibrator device has been set | |
bool | calibrateSingleJoint (int j) override |
calibrateSingleJoint: call the calibration procedure for the single joint | |
bool | calibrateWholePart () override |
calibrateWholePart: call the procedure for calibrating the whole device | |
bool | homingSingleJoint (int j) override |
homingSingleJoint: call the homing procedure for a single joint | |
bool | homingWholePart () override |
homingWholePart: call the homing procedure for a the whole part/device | |
bool | parkSingleJoint (int j, bool _wait=true) override |
parkSingleJoint(): start the parking procedure for the single joint | |
bool | parkWholePart () override |
parkWholePart: start the parking procedure for the whole part | |
bool | quitCalibrate () override |
quitCalibrate: interrupt the calibration procedure | |
bool | quitPark () override |
quitPark: interrupt the park procedure | |
bool | getRefCurrents (double *t) override |
Get the reference value of the currents for all motors. | |
bool | getRefCurrent (int j, double *t) override |
Get the reference value of the current for a single motor. | |
bool | setRefCurrents (const double *refs) override |
Set the reference value of the currents for all motors. | |
bool | setRefCurrent (int j, double ref) override |
Set the reference value of the current for a single motor. | |
bool | setRefCurrents (const int n_joint, const int *joints, const double *refs) override |
Set the reference value of the current for a group of motors. | |
bool | getCurrents (double *vals) override |
bool | getCurrent (int j, double *val) override |
bool | getCurrentRange (int j, double *min, double *max) override |
Get the full scale of the current measurement for a given motor (e.g. | |
bool | getCurrentRanges (double *min, double *max) override |
Get the full scale of the current measurements for all motors motor (e.g. | |
bool | setRefDutyCycle (int j, double v) override |
Sets the reference dutycycle to a single motor. | |
bool | setRefDutyCycles (const double *v) override |
Sets the reference dutycycle for all the motors. | |
bool | getRefDutyCycle (int j, double *ref) override |
Gets the last reference sent using the setRefDutyCycle function. | |
bool | getRefDutyCycles (double *refs) override |
Gets the last reference sent using the setRefDutyCycles function. | |
bool | getDutyCycle (int j, double *out) override |
Gets the current dutycycle of the output of the amplifier (i.e. | |
bool | getDutyCycles (double *outs) override |
Gets the current dutycycle of the output of the amplifier (i.e. | |
yarp::dev::ReturnValue | isJointBraked (int j, bool &braked) const override |
Check is the joint brake is currently active. | |
yarp::dev::ReturnValue | setManualBrakeActive (int j, bool active) override |
Enables/Disables manually the joint brake. | |
yarp::dev::ReturnValue | setAutoBrakeEnabled (int j, bool enabled) override |
Enables/Disables the automatic joint brake. | |
yarp::dev::ReturnValue | getAutoBrakeEnabled (int j, bool &enabled) const override |
checks if the automatic joint brake mode is enabled or disabled. | |
yarp::dev::ReturnValue | getAxes (size_t &axes) override |
Get the number of controlled axes. | |
yarp::dev::ReturnValue | setDesiredVelocity (int jnt, double vel) override |
Set the velocity of single joint. | |
yarp::dev::ReturnValue | setDesiredVelocity (const std::vector< double > &vels) override |
Set the velocity of all joints. | |
yarp::dev::ReturnValue | setDesiredVelocity (const std::vector< int > &jnts, const std::vector< double > &vels) override |
Set the velocity of a subset of joints. | |
yarp::dev::ReturnValue | getDesiredVelocity (const int jnt, double &vel) override |
Get the last reference velocity set by setDesiredVelocity() for a single joint. | |
yarp::dev::ReturnValue | getDesiredVelocity (std::vector< double > &vels) override |
Get the last reference velocity set by setDesiredVelocity() for all joints. | |
yarp::dev::ReturnValue | getDesiredVelocity (const std::vector< int > &jnts, std::vector< double > &vels) override |
Get the last reference velocity set by setDesiredVelocity() for a group of joints. | |
![]() | |
virtual | ~IPidControl () |
Destructor. | |
![]() | |
virtual | ~IPositionControl () |
Destructor. | |
![]() | |
virtual | ~IVelocityControl () |
Destructor. | |
![]() | |
virtual | ~IEncodersTimed () |
Destructor. | |
![]() | |
virtual | ~IEncoders () |
Destructor. | |
![]() | |
virtual | ~IMotorEncoders () |
Destructor. | |
![]() | |
virtual | ~IMotor () |
Destructor. | |
![]() | |
virtual | ~IAmplifierControl () |
Destructor. | |
![]() | |
virtual | ~IControlLimits () |
Destructor. | |
![]() | |
virtual | ~IAxisInfo () |
Destructor. | |
![]() | |
virtual | ~IPreciselyTimed () |
![]() | |
IControlCalibration () | |
virtual | ~IControlCalibration () |
Destructor. | |
virtual bool | setCalibrator (ICalibrator *c) |
Set the calibrator object to be used to calibrate the robot. | |
![]() | |
virtual | ~ITorqueControl () |
Destructor. | |
![]() | |
virtual | ~IImpedanceControl () |
Destructor. | |
![]() | |
virtual | ~IControlMode () |
![]() | |
DeviceDriver () | |
DeviceDriver (const DeviceDriver &other)=delete | |
DeviceDriver (DeviceDriver &&other) noexcept=delete | |
DeviceDriver & | operator= (const DeviceDriver &other)=delete |
DeviceDriver & | operator= (DeviceDriver &&other) noexcept=delete |
virtual | ~DeviceDriver () |
virtual std::string | id () const |
Return the id assigned to the PolyDriver. | |
virtual void | setId (const std::string &id) |
Set the id for this device. | |
template<class T > | |
bool | view (T *&x) |
Get an interface to the device driver. | |
virtual DeviceDriver * | getImplementation () |
Some drivers are bureaucrats, pointing at others. | |
![]() | |
virtual | ~IPositionDirect () |
Destructor. | |
![]() | |
virtual | ~IVelocityDirect () |
Destructor. | |
![]() | |
virtual | ~IInteractionMode () |
Destructor. | |
![]() | |
IRemoteCalibrator () | |
This interface is meant to remotize the access of the calibration device in order to allow users to remotely call the calibration procedure for a single joint or the whole device and let the calibrator do the job. | |
virtual | ~IRemoteCalibrator ()=default |
virtual bool | setCalibratorDevice (yarp::dev::IRemoteCalibrator *dev) |
setCalibratorDevice: store the pointer to the calibrator device. | |
virtual yarp::dev::IRemoteCalibrator * | getCalibratorDevice () |
getCalibratorDevice: return the pointer stored with the setCalibratorDevice | |
virtual void | releaseCalibratorDevice () |
releaseCalibratorDevice: reset the internal pointer to NULL when stop using the calibrator | |
![]() | |
virtual | ~IRemoteVariables () |
Destructor. | |
![]() | |
virtual | ~IPWMControl () |
![]() | |
virtual | ~ICurrentControl () |
Destructor. | |
![]() | |
virtual | ~IJointFault () |
![]() | |
virtual | ~IJointBrake () |
![]() | |
RemoteControlBoard_ParamsParser () | |
~RemoteControlBoard_ParamsParser () override=default | |
bool | parseParams (const yarp::os::Searchable &config) override |
Parse the DeviceDriver parameters. | |
std::string | getDeviceClassName () const override |
Get the name of the DeviceDriver class. | |
std::string | getDeviceName () const override |
Get the name of the device (i.e. | |
std::string | getDocumentationOfDeviceParams () const override |
Get the documentation of the DeviceDriver's parameters. | |
std::vector< std::string > | getListOfParams () const override |
Return a list of all params used by the device. | |
bool | getParamValue (const std::string ¶mName, std::string ¶mValue) const override |
Return the value (represented as a string) of the requested parameter. | |
std::string | getConfiguration () const override |
Return the configuration of the device. | |
![]() | |
virtual | ~IDeviceDriverParams () |
Protected Member Functions | |
bool | isLive () |
bool | send1V (int v) |
bool | send2V (int v1, int v2) |
bool | send2V1I (int v1, int v2, int axis) |
bool | send1V1I (int v, int axis) |
bool | send3V1I (int v1, int v2, int v3, int j) |
bool | set1V (int code) |
Send a SET command without parameters and wait for a reply. | |
bool | set1V2D (int code, double v) |
Send a SET command and an additional double valued variable and then wait for a reply. | |
bool | set1V1I (int code, int v) |
Send a SET command with an additional integer valued variable and then wait for a reply. | |
bool | get1V1D (int code, double &v) const |
Send a GET command expecting a double value in return. | |
bool | get1V1I (int code, int &v) const |
Send a GET command expecting an integer value in return. | |
bool | set1V1I1D (int code, int j, double val) |
Helper method to set a double value to a single axis. | |
bool | set1V1I2D (int code, int j, double val1, double val2) |
bool | set1VDA (int v, const double *val) |
Helper method used to set an array of double to all axes. | |
bool | set2V1DA (int v1, int v2, const double *val) |
bool | set2V2DA (int v1, int v2, const double *val1, const double *val2) |
bool | set1V1I1IA1DA (int v, const int len, const int *val1, const double *val2) |
bool | set2V1I1D (int v1, int v2, int axis, double val) |
bool | setValWithPidType (int voc, PidControlTypeEnum type, int axis, double val) |
bool | setValWithPidType (int voc, PidControlTypeEnum type, const double *val_arr) |
bool | getValWithPidType (int voc, PidControlTypeEnum type, int j, double *val) |
bool | getValWithPidType (int voc, PidControlTypeEnum type, double *val) |
bool | set2V1I (int v1, int v2, int axis) |
bool | get1V1I1D (int v, int j, double *val) |
Helper method used to get a double value from the remote peer. | |
bool | get1V1I1I (int v, int j, int *val) |
Helper method used to get an integer value from the remote peer. | |
bool | get2V1I1D (int v1, int v2, int j, double *val) |
bool | get2V1I2D (int v1, int v2, int j, double *val1, double *val2) |
bool | get1V1I2D (int code, int axis, double *v1, double *v2) |
bool | get1V1I1B (int v, int j, bool &val) |
Helper method used to get a double value from the remote peer. | |
bool | get1V1I1IA1B (int v, const int len, const int *val1, bool &retVal) |
bool | get2V1I1IA1DA (int v1, int v2, const int n_joints, const int *joints, double *retVals, std::string functionName="") |
bool | get1V1B (int v, bool &val) |
bool | get1VIA (int v, int *val) |
Helper method to get an array of integers from the remote peer. | |
bool | get1VDA (int v, double *val) |
Helper method to get an array of double from the remote peer. | |
bool | get1V1DA (int v1, double *val) |
Helper method to get an array of double from the remote peer. | |
bool | get2V1DA (int v1, int v2, double *val) |
Helper method to get an array of double from the remote peer. | |
bool | get2V2DA (int v1, int v2, double *val1, double *val2) |
bool | get1V1I1S (int code, int j, std::string &name) |
bool | get1V1I1IA1DA (int v, const int len, const int *val1, double *val2) |
Additional Inherited Members | |
![]() | |
const std::string | m_device_classname = {"RemoteControlBoard"} |
const std::string | m_device_name = {"remote_controlboard"} |
bool | m_parser_is_strict = false |
const parser_version_type | m_parser_version = {} |
std::string | m_provided_configuration |
const std::string | m_remote_defaultValue = {""} |
const std::string | m_local_defaultValue = {""} |
const std::string | m_writeStrict_defaultValue = {""} |
const std::string | m_carrier_defaultValue = {"fast_tcp"} |
const std::string | m_carrier_cmd_defaultValue = {"fast_tcp"} |
const std::string | m_timeout_defaultValue = {"0.5"} |
const std::string | m_local_qos_enable_defaultValue = {"false"} |
const std::string | m_local_qos_thread_priority_defaultValue = {"0"} |
const std::string | m_local_qos_thread_policy_defaultValue = {"0"} |
const std::string | m_local_qos_packet_priority_defaultValue = {""} |
const std::string | m_remote_qos_enable_defaultValue = {"false"} |
const std::string | m_remote_qos_thread_priority_defaultValue = {"0"} |
const std::string | m_remote_qos_thread_policy_defaultValue = {"0"} |
const std::string | m_remote_qos_packet_priority_defaultValue = {""} |
const std::string | m_diagnostic_defaultValue = {"false"} |
std::string | m_remote = {} |
std::string | m_local = {} |
std::string | m_writeStrict = {} |
std::string | m_carrier = {"fast_tcp"} |
std::string | m_carrier_cmd = {"fast_tcp"} |
float | m_timeout = {0.5} |
bool | m_local_qos_enable = {false} |
int | m_local_qos_thread_priority = {0} |
int | m_local_qos_thread_policy = {0} |
std::string | m_local_qos_packet_priority = {} |
bool | m_remote_qos_enable = {false} |
int | m_remote_qos_thread_priority = {0} |
int | m_remote_qos_thread_policy = {0} |
std::string | m_remote_qos_packet_priority = {} |
bool | m_diagnostic = {false} |
remote_controlboard
: The client side of the control board, connects to a remote controlboard using the YARP network.
This device communicates using the YARP ports opened the controlBoard_nws_yarp device to use a device exposing controlboard method even from a different process (or even computer) from the one that opened the controlboard device.
Parameters required by this device are shown in class: RemoteControlBoard_ParamsParser
Definition at line 55 of file RemoteControlBoard.h.
|
default |
|
delete |
|
delete |
|
overridedefault |
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 2007 of file RemoteControlBoard.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 2012 of file RemoteControlBoard.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Implements yarp::dev::IControlCalibration.
Definition at line 2022 of file RemoteControlBoard.cpp.
|
overridevirtual |
Calibrate robot by using an external calibrator.
The external calibrator must be previously set by calling the setCalibration() method.
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 2002 of file RemoteControlBoard.cpp.
calibrateSingleJoint: call the calibration procedure for the single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2652 of file RemoteControlBoard.cpp.
|
overridevirtual |
calibrateWholePart: call the procedure for calibrating the whole device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2657 of file RemoteControlBoard.cpp.
Check if the calibration is terminated, on a particular joint.
Non blocking.
Implements yarp::dev::IControlCalibration.
Definition at line 2061 of file RemoteControlBoard.cpp.
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 1732 of file RemoteControlBoard.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 1727 of file RemoteControlBoard.cpp.
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 1722 of file RemoteControlBoard.cpp.
|
overridevirtual |
Close the device driver and stop the port connections.
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 319 of file RemoteControlBoard.cpp.
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 1892 of file RemoteControlBoard.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 1269 of file RemoteControlBoard.cpp.
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 1887 of file RemoteControlBoard.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 1284 of file RemoteControlBoard.cpp.
Definition at line 853 of file RemoteControlBoard.cpp.
Send a GET command expecting a double value in return.
code | is the Vocab code of the GET command. |
v | is a reference to the return variable. |
Definition at line 437 of file RemoteControlBoard.cpp.
Helper method to get an array of double from the remote peer.
v1 | is the name of the command |
val | is the array of double |
Definition at line 921 of file RemoteControlBoard.cpp.
Send a GET command expecting an integer value in return.
code | is the Vocab code of the GET command. |
v | is a reference to the return variable. |
Definition at line 457 of file RemoteControlBoard.cpp.
Helper method used to get a double value from the remote peer.
v | is the command to query for |
j | is the axis number |
val | is the return value |
Definition at line 771 of file RemoteControlBoard.cpp.
Helper method used to get a double value from the remote peer.
v | is the command to query for |
j | is the axis number |
val | is the return value |
Definition at line 681 of file RemoteControlBoard.cpp.
Helper method used to get an integer value from the remote peer.
v | is the command to query for |
j | is the axis number |
val | is the return value |
Definition at line 699 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 786 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 1032 of file RemoteControlBoard.cpp.
Definition at line 1016 of file RemoteControlBoard.cpp.
Definition at line 754 of file RemoteControlBoard.cpp.
Helper method to get an array of double from the remote peer.
v | is the name of the command |
val | is the array of double |
Definition at line 894 of file RemoteControlBoard.cpp.
Helper method to get an array of integers from the remote peer.
v | is the name of the command |
val | is the array of double |
Definition at line 867 of file RemoteControlBoard.cpp.
Helper method to get an array of double from the remote peer.
v1 | is the name of the command |
v2 | v2 |
val | is the array of double |
Definition at line 948 of file RemoteControlBoard.cpp.
Definition at line 716 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 807 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 735 of file RemoteControlBoard.cpp.
Definition at line 976 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAmplifierControl.
Definition at line 1897 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAmplifierControl.
Definition at line 1902 of file RemoteControlBoard.cpp.
|
overridevirtual |
checks if the automatic joint brake mode is enabled or disabled.
j | joint number |
enabled | is true the automatic joint brake mode is enabled |
Implements yarp::dev::IJointBrake.
Definition at line 2936 of file RemoteControlBoard.cpp.
Get the number of controlled axes.
This command asks the number of controlled axes for the current physical interface.
ax | pointer to storage |
Implements yarp::dev::IPositionControl.
Definition at line 1074 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the number of controlled axes.
axes | returned number of controllable axes |
Implements yarp::dev::IVelocityDirect.
Definition at line 2950 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAxisInfo.
Definition at line 1989 of file RemoteControlBoard.cpp.
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 2326 of file RemoteControlBoard.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 2344 of file RemoteControlBoard.cpp.
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 2335 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAmplifierControl.
Definition at line 2792 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the current impedandance limits for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 2299 of file RemoteControlBoard.cpp.
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 2801 of file RemoteControlBoard.cpp.
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 2806 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAmplifierControl.
Definition at line 2783 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the last reference velocity set by setDesiredVelocity() for a single joint.
jnt | joint number |
vel | returns the velocity reference for the specified joint. |
Implements yarp::dev::IVelocityDirect.
Definition at line 3014 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the last reference velocity set by setDesiredVelocity() for a group of joints.
jnts | vector containing the ids of the joints to control. |
vels | vector containing the velocity references of the joints belonging to the required subset. |
Implements yarp::dev::IVelocityDirect.
Definition at line 3038 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the last reference velocity set by setDesiredVelocity() for all joints.
vels | vector containing the velocity references of all joints. |
Implements yarp::dev::IVelocityDirect.
Definition at line 3026 of file RemoteControlBoard.cpp.
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 2882 of file RemoteControlBoard.cpp.
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 2891 of file RemoteControlBoard.cpp.
Read the value of an encoder.
j | encoder number |
v | pointer to storage for the return value |
Implements yarp::dev::IEncoders.
Definition at line 1355 of file RemoteControlBoard.cpp.
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 1418 of file RemoteControlBoard.cpp.
Read the instantaneous acceleration of all axes.
accs | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 1427 of file RemoteControlBoard.cpp.
Read the position of all axes.
encs | pointer to the array that will contain the output |
Implements yarp::dev::IEncoders.
Definition at line 1376 of file RemoteControlBoard.cpp.
Read the istantaneous speed of an axis.
j | axis number |
sp | pointer to storage for the output |
Implements yarp::dev::IEncoders.
Definition at line 1398 of file RemoteControlBoard.cpp.
Read the instantaneous speed of all axes.
spds | pointer to storage for the output values |
Implements yarp::dev::IEncoders.
Definition at line 1408 of file RemoteControlBoard.cpp.
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 1387 of file RemoteControlBoard.cpp.
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 1365 of file RemoteControlBoard.cpp.
Get the gearbox ratio for a specific motor.
m | motor number |
val | retrieved gearbox ratio |
Reimplemented from yarp::dev::IMotor.
Definition at line 1528 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get current impedance gains (stiffness,damping,offset) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 2227 of file RemoteControlBoard.cpp.
Get current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 2248 of file RemoteControlBoard.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 2533 of file RemoteControlBoard.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 2542 of file RemoteControlBoard.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 2561 of file RemoteControlBoard.cpp.
|
overridevirtual |
Reimplemented from yarp::dev::IAxisInfo.
Definition at line 1994 of file RemoteControlBoard.cpp.
|
overridevirtual |
Get the time stamp for the last read data.
Implements yarp::dev::IPreciselyTimed.
Definition at line 1664 of file RemoteControlBoard.cpp.
|
overridevirtual |
Implements yarp::dev::IJointFault.
Definition at line 1829 of file RemoteControlBoard.cpp.
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 1970 of file RemoteControlBoard.cpp.
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 1912 of file RemoteControlBoard.cpp.
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 1572 of file RemoteControlBoard.cpp.
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 1633 of file RemoteControlBoard.cpp.
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 1642 of file RemoteControlBoard.cpp.
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 1562 of file RemoteControlBoard.cpp.
Read the position of all motor encoders.
encs | pointer to the array that will contain the output |
Implements yarp::dev::IMotorEncoders.
Definition at line 1593 of file RemoteControlBoard.cpp.
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 1615 of file RemoteControlBoard.cpp.
Read the instantaneous speed of all motor encoders.
spds | pointer to storage for the output values |
Implements yarp::dev::IMotorEncoders.
Definition at line 1624 of file RemoteControlBoard.cpp.
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 1604 of file RemoteControlBoard.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 1582 of file RemoteControlBoard.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 2162 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1917 of file RemoteControlBoard.cpp.
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 1651 of file RemoteControlBoard.cpp.
Get the number of available motors.
num | retrieved number of available motors |
Implements yarp::dev::IMotor.
Definition at line 1492 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1927 of file RemoteControlBoard.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 1163 of file RemoteControlBoard.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 1153 of file RemoteControlBoard.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 1244 of file RemoteControlBoard.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 1249 of file RemoteControlBoard.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 1158 of file RemoteControlBoard.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 1316 of file RemoteControlBoard.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 1321 of file RemoteControlBoard.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 1234 of file RemoteControlBoard.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 1239 of file RemoteControlBoard.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 1193 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1956 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1937 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1946 of file RemoteControlBoard.cpp.
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 1782 of file RemoteControlBoard.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 1787 of file RemoteControlBoard.cpp.
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 1792 of file RemoteControlBoard.cpp.
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 2727 of file RemoteControlBoard.cpp.
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 2722 of file RemoteControlBoard.cpp.
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 2854 of file RemoteControlBoard.cpp.
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 2877 of file RemoteControlBoard.cpp.
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 2475 of file RemoteControlBoard.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 2485 of file RemoteControlBoard.cpp.
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 2480 of file RemoteControlBoard.cpp.
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 1767 of file RemoteControlBoard.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 1772 of file RemoteControlBoard.cpp.
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 1777 of file RemoteControlBoard.cpp.
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 2070 of file RemoteControlBoard.cpp.
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 2075 of file RemoteControlBoard.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 2524 of file RemoteControlBoard.cpp.
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 2519 of file RemoteControlBoard.cpp.
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 2514 of file RemoteControlBoard.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 1440 of file RemoteControlBoard.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 1471 of file RemoteControlBoard.cpp.
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 1692 of file RemoteControlBoard.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 1702 of file RemoteControlBoard.cpp.
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 1697 of file RemoteControlBoard.cpp.
Get temperature of a motor.
m | motor number |
val | retrieved motor temperature |
Implements yarp::dev::IMotor.
Definition at line 1497 of file RemoteControlBoard.cpp.
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 1518 of file RemoteControlBoard.cpp.
Get temperature of all the motors.
vals | pointer to an array containing all motor temperatures |
Implements yarp::dev::IMotor.
Definition at line 1507 of file RemoteControlBoard.cpp.
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 2195 of file RemoteControlBoard.cpp.
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 2213 of file RemoteControlBoard.cpp.
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 2218 of file RemoteControlBoard.cpp.
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 2204 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 642 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 623 of file RemoteControlBoard.cpp.
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 1980 of file RemoteControlBoard.cpp.
homingSingleJoint: call the homing procedure for a single joint
j | joint to be calibrated |
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2667 of file RemoteControlBoard.cpp.
|
overridevirtual |
homingWholePart: call the homing procedure for a the whole part/device
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2672 of file RemoteControlBoard.cpp.
isCalibratorDevicePresent: check if a calibrator device has been set
Reimplemented from yarp::dev::IRemoteCalibrator.
Definition at line 2637 of file RemoteControlBoard.cpp.
|
overridevirtual |
Check is the joint brake is currently active.
j | joint number |
braked | is true if the joint is currently braked |
Implements yarp::dev::IJointBrake.
Definition at line 2902 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 102 of file RemoteControlBoard.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 1299 of file RemoteControlBoard.cpp.
|
overridevirtual |
Open the DeviceDriver.
config | is a list of parameters for the device. Which parameters are effective for your device can vary. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device). |
Reimplemented from yarp::dev::DeviceDriver.
Definition at line 117 of file RemoteControlBoard.cpp.
|
delete |
|
delete |
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 2017 of file RemoteControlBoard.cpp.
parkSingleJoint(): start the parking procedure for the single joint
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2683 of file RemoteControlBoard.cpp.
|
overridevirtual |
parkWholePart: start the parking procedure for the whole part
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2688 of file RemoteControlBoard.cpp.
Set new reference point for all axes.
refs | array, new reference points. |
Implements yarp::dev::IPositionControl.
Definition at line 1687 of file RemoteControlBoard.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 1682 of file RemoteControlBoard.cpp.
Set new reference point for a single axis.
j | joint number |
ref | specifies the new ref point |
Implements yarp::dev::IPositionControl.
Definition at line 1677 of file RemoteControlBoard.cpp.
|
overridevirtual |
quitCalibrate: interrupt the calibration procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2698 of file RemoteControlBoard.cpp.
|
overridevirtual |
quitPark: interrupt the park procedure
Implements yarp::dev::IRemoteCalibrator.
Definition at line 2708 of file RemoteControlBoard.cpp.
Set relative position, all joints.
deltas | pointer to the relative commands |
Implements yarp::dev::IPositionControl.
Definition at line 1717 of file RemoteControlBoard.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 1712 of file RemoteControlBoard.cpp.
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 1707 of file RemoteControlBoard.cpp.
Reset encoder, single joint.
Set the encoder value to zero
j | encoder number |
Implements yarp::dev::IEncoders.
Definition at line 1335 of file RemoteControlBoard.cpp.
|
overridevirtual |
Reset encoders.
Set the encoders value to zero
Implements yarp::dev::IEncoders.
Definition at line 1340 of file RemoteControlBoard.cpp.
Reset motor encoder, single motor.
Set the encoder value to zero.
m | motor number |
Implements yarp::dev::IMotorEncoders.
Definition at line 1542 of file RemoteControlBoard.cpp.
|
overridevirtual |
Reset motor encoders.
Set the motor encoders value to zero.
Implements yarp::dev::IMotorEncoders.
Definition at line 1547 of file RemoteControlBoard.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 1254 of file RemoteControlBoard.cpp.
Definition at line 341 of file RemoteControlBoard.cpp.
Definition at line 377 of file RemoteControlBoard.cpp.
Definition at line 352 of file RemoteControlBoard.cpp.
Definition at line 364 of file RemoteControlBoard.cpp.
Definition at line 389 of file RemoteControlBoard.cpp.
Send a SET command without parameters and wait for a reply.
code | is the command Vocab identifier. |
Definition at line 403 of file RemoteControlBoard.cpp.
Send a SET command with an additional integer valued variable and then wait for a reply.
code | is the command to send. |
v | is an integer valued parameter. |
Definition at line 425 of file RemoteControlBoard.cpp.
Helper method to set a double value to a single axis.
code | is the name of the command to be transmitted |
j | is the axis |
val | is the double value |
Definition at line 477 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 555 of file RemoteControlBoard.cpp.
Definition at line 488 of file RemoteControlBoard.cpp.
Send a SET command and an additional double valued variable and then wait for a reply.
code | is the command to send. |
v | is a double valued parameter. |
Definition at line 413 of file RemoteControlBoard.cpp.
Helper method used to set an array of double to all axes.
v | is the command to set |
val | is the double array (of length nj) |
Definition at line 501 of file RemoteControlBoard.cpp.
Definition at line 517 of file RemoteControlBoard.cpp.
Definition at line 670 of file RemoteControlBoard.cpp.
Definition at line 577 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 534 of file RemoteControlBoard.cpp.
|
overridevirtual |
Enables/Disables the automatic joint brake.
If enabled, the firmware can automatically choose when to enable the joint brake (for example when the joint is in hardware_fault mode).
j | joint number |
enabled | true to enable the automatic joint brake |
Implements yarp::dev::IJointBrake.
Definition at line 2925 of file RemoteControlBoard.cpp.
|
overridevirtual |
Start calibration, this method is very often platform specific.
Reimplemented from yarp::dev::IControlCalibration.
Definition at line 2041 of file RemoteControlBoard.cpp.
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 2363 of file RemoteControlBoard.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 2379 of file RemoteControlBoard.cpp.
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 2404 of file RemoteControlBoard.cpp.
|
overridevirtual |
Set the velocity of all joints.
vels | vector containing joint velocities for all joints |
Implements yarp::dev::IVelocityDirect.
Definition at line 2977 of file RemoteControlBoard.cpp.
|
overridevirtual |
Set the velocity of a subset of joints.
jnts | vector containing the ids of the joints to control. |
vels | vector containing the joint velocities for the required subset. |
Implements yarp::dev::IVelocityDirect.
Definition at line 2993 of file RemoteControlBoard.cpp.
|
overridevirtual |
Set the velocity of single joint.
jnt | joint number |
vel | speed value |
Implements yarp::dev::IVelocityDirect.
Definition at line 2962 of file RemoteControlBoard.cpp.
Set the value of the encoder for a given joint.
j | encoder number |
val | new value |
Implements yarp::dev::IEncoders.
Definition at line 1345 of file RemoteControlBoard.cpp.
Set the value of all encoders.
vals | pointer to the new values |
Implements yarp::dev::IEncoders.
Definition at line 1350 of file RemoteControlBoard.cpp.
Set the gearbox ratio for a specific motor.
m | motor number |
gearbox | ratio to be set |
Reimplemented from yarp::dev::IMotor.
Definition at line 1533 of file RemoteControlBoard.cpp.
Set current impedance gains (stiffness,damping) for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 2268 of file RemoteControlBoard.cpp.
Set current force Offset for a specific joint.
Implements yarp::dev::IImpedanceControl.
Definition at line 2284 of file RemoteControlBoard.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 2570 of file RemoteControlBoard.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 2587 of file RemoteControlBoard.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 2613 of file RemoteControlBoard.cpp.
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 1965 of file RemoteControlBoard.cpp.
|
overridevirtual |
Enables/Disables manually the joint brake.
j | joint number |
active | true to enable the joint brake |
Implements yarp::dev::IJointBrake.
Definition at line 2914 of file RemoteControlBoard.cpp.
Implements yarp::dev::IAmplifierControl.
Definition at line 1907 of file RemoteControlBoard.cpp.
Set the value of the motor encoder for a given motor.
m | motor number |
val | new value |
Implements yarp::dev::IMotorEncoders.
Definition at line 1552 of file RemoteControlBoard.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 1557 of file RemoteControlBoard.cpp.
Set the value of all motor encoders.
vals | pointer to the new values |
Implements yarp::dev::IMotorEncoders.
Definition at line 1567 of file RemoteControlBoard.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 2141 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1922 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1932 of file RemoteControlBoard.cpp.
|
overridevirtual |
Set new pid value for a joint axis.
pidtype | the id of the pid that will be affected by the command (e.g. position, velocity etc) |
j | joint number |
pid | new pid value |
Implements yarp::dev::IPidControl.
Definition at line 1081 of file RemoteControlBoard.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 1143 of file RemoteControlBoard.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 1148 of file RemoteControlBoard.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 1326 of file RemoteControlBoard.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 1133 of file RemoteControlBoard.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 1138 of file RemoteControlBoard.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 1104 of file RemoteControlBoard.cpp.
Set new position for a single axis.
j | joint number |
ref | specifies the new ref point |
Implements yarp::dev::IPositionDirect.
Definition at line 2427 of file RemoteControlBoard.cpp.
Set new position for a set of axis.
refs | specifies the new reference points |
Implements yarp::dev::IPositionDirect.
Definition at line 2461 of file RemoteControlBoard.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 2442 of file RemoteControlBoard.cpp.
Reimplemented from yarp::dev::IAmplifierControl.
Definition at line 1951 of file RemoteControlBoard.cpp.
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 1752 of file RemoteControlBoard.cpp.
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 1762 of file RemoteControlBoard.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 1757 of file RemoteControlBoard.cpp.
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 2747 of file RemoteControlBoard.cpp.
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 2732 of file RemoteControlBoard.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 2763 of file RemoteControlBoard.cpp.
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 2814 of file RemoteControlBoard.cpp.
Sets the reference dutycycle for all the motors.
refs | the dutycycle, expressed as percentage (-100% +100%) |
Implements yarp::dev::IPWMControl.
Definition at line 2834 of file RemoteControlBoard.cpp.
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 1737 of file RemoteControlBoard.cpp.
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 1747 of file RemoteControlBoard.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 1742 of file RemoteControlBoard.cpp.
Set the reference value of the torque for a given joint.
j | joint number |
t | new value |
Implements yarp::dev::ITorqueControl.
Definition at line 2099 of file RemoteControlBoard.cpp.
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 2080 of file RemoteControlBoard.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 2119 of file RemoteControlBoard.cpp.
|
overridevirtual |
Implements yarp::dev::IRemoteVariables.
Definition at line 1456 of file RemoteControlBoard.cpp.
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 1523 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 605 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 589 of file RemoteControlBoard.cpp.
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 1975 of file RemoteControlBoard.cpp.
|
overridevirtual |
Stop motion, multiple joints.
Implements yarp::dev::IPositionControl.
Definition at line 1821 of file RemoteControlBoard.cpp.
Stop motion for subset of joints.
joints | pointer to the array of joint numbers |
Implements yarp::dev::IPositionControl.
Definition at line 1802 of file RemoteControlBoard.cpp.
Stop motion, single joint.
j | joint number |
Implements yarp::dev::IPositionControl.
Definition at line 1797 of file RemoteControlBoard.cpp.
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 1869 of file RemoteControlBoard.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 2494 of file RemoteControlBoard.cpp.
Start motion at a given speed, single joint.
j | joint number |
sp | speed value |
Implements yarp::dev::IVelocityControl.
Definition at line 1854 of file RemoteControlBoard.cpp.
|
protected |
Definition at line 89 of file RemoteControlBoard.h.
|
protected |
Definition at line 84 of file RemoteControlBoard.h.
|
protected |
Definition at line 85 of file RemoteControlBoard.h.
|
protected |
Definition at line 96 of file RemoteControlBoard.h.
|
protected |
Definition at line 97 of file RemoteControlBoard.h.
|
protected |
Definition at line 98 of file RemoteControlBoard.h.
|
protected |
Definition at line 100 of file RemoteControlBoard.h.
|
mutableprotected |
Definition at line 102 of file RemoteControlBoard.h.
|
protected |
Definition at line 106 of file RemoteControlBoard.h.
|
protected |
Definition at line 86 of file RemoteControlBoard.h.
|
protected |
Definition at line 103 of file RemoteControlBoard.h.
Definition at line 104 of file RemoteControlBoard.h.
|
protected |
Definition at line 83 of file RemoteControlBoard.h.
|
protected |
Definition at line 88 of file RemoteControlBoard.h.
Definition at line 91 of file RemoteControlBoard.h.
Definition at line 90 of file RemoteControlBoard.h.