|
| RemoteControlBoardRemapper ()=default |
|
| RemoteControlBoardRemapper (const RemoteControlBoardRemapper &)=delete |
|
| RemoteControlBoardRemapper (RemoteControlBoardRemapper &&)=delete |
|
RemoteControlBoardRemapper & | operator= (const RemoteControlBoardRemapper &)=delete |
|
RemoteControlBoardRemapper & | operator= (RemoteControlBoardRemapper &&)=delete |
|
| ~RemoteControlBoardRemapper () override=default |
|
bool | open (yarp::os::Searchable &prop) override |
| Open the device driver. More...
|
|
bool | close () override |
| Close the device driver by deallocating all resources and closing ports. More...
|
|
| 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 |
|