6#ifndef YARP_DEV_CONTROLBOARDREMAPPER_CONTROLBOARDREMAPPER_H
7#define YARP_DEV_CONTROLBOARDREMAPPER_CONTROLBOARDREMAPPER_H
24 #pragma warning(disable:4355)
94 std::vector<std::string> axesNames;
98 int controlledJoints{0};
104 std::string partName;
119 void setNrOfControlledAxes(
const size_t nrOfControlledAxes);
126 bool updateAxesName();
131 void configureBuffers();
136 bool usingAxesNamesForAttachAll{
false};
137 bool usingNetworksForAttachAll{
false};
171 bool setControlModeAllAxes(
const int cm);
192 bool close()
override;
250 bool getAxes(
int *ax)
override;
256 bool positionMove(
const int n_joints,
const int *joints,
const double *refs)
override;
268 bool relativeMove(
const int n_joints,
const int *joints,
const double *deltas)
override;
274 bool checkMotionDone(
const int n_joints,
const int *joints,
bool *flags)
override;
280 bool setRefSpeeds(
const int n_joints,
const int *joints,
const double *spds)
override;
286 bool setRefAccelerations(
const int n_joints,
const int *joints,
const double *accs)
override;
292 bool getRefSpeeds(
const int n_joints,
const int *joints,
double *spds)
override;
300 bool stop(
int j)
override;
302 bool stop()
override;
304 bool stop(
const int n_joints,
const int *joints)
override;
392 bool getPWM(
int m,
double *val)
override;
396 bool setPWMLimit(
int m,
const double val)
override;
401 bool setLimits(
int j,
double min,
double max)
override;
403 bool getLimits(
int j,
double *min,
double *max)
override;
405 bool setVelLimits(
int j,
double min,
double max)
override;
407 bool getVelLimits(
int j,
double *min,
double *max)
override;
467 bool getAxisName(
int j, std::string &name)
override;
479 bool setRefTorques(
const int n_joint,
const int *joints,
const double *t)
override;
485 bool setImpedance(
int j,
double stiff,
double damp)
override;
489 bool getTorque(
int j,
double *t)
override;
497 bool getImpedance(
int j,
double *stiff,
double *damp)
override;
501 bool getCurrentImpedanceLimit(
int j,
double *min_stiff,
double *max_stiff,
double *min_damp,
double *max_damp)
override;
508 bool getControlModes(
const int n_joint,
const int *joints,
int *modes)
override;
512 bool setControlModes(
const int n_joints,
const int *joints,
int *modes)
override;
518 bool setPositions(
const int n_joints,
const int *joints,
const double *dpos)
override;
526 bool getRefPositions(
const int n_joint,
const int *joints,
double *refs)
override;
531 bool velocityMove(
const int n_joints,
const int *joints,
const double *spds)
override;
537 bool getRefVelocities(
const int n_joint,
const int *joints,
double *vels)
override;
565 bool getCurrent(
int m,
double *curr)
override;
577 bool setRefCurrents(
const int n_motor,
const int *motors,
const double *currs)
override;
define control board standard interfaces
Class storing the decomposition of a subset of the total remapped axes of the remapped controlboard i...
controlboardremapper : device that takes a list of axes from multiple controlboards and expose them a...
bool parkWholePart() override
parkWholePart: start the parking procedure for the whole part
bool setImpedance(int j, double stiff, double damp) override
Set current impedance gains (stiffness,damping) for a specific joint.
bool getPidErrorLimit(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override
Get the error limit for the controller on a specific joint.
bool setRefAccelerations(const double *accs) override
Set reference acceleration on all joints.
bool resetMotorEncoder(int m) override
Reset motor encoder, single motor.
ControlBoardRemapper & operator=(ControlBoardRemapper &&)=delete
bool getTorqueRange(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool getTargetPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override
Gets number of counts per revolution for motor encoder m.
bool getAmpStatus(int *st) override
bool setTemperatureLimit(int m, const double val) override
Set the temperature limit for a specific motor.
bool setPid(const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override
ControlBoard methods.
bool setRefCurrent(int m, double curr) override
Set the reference value of the current for a single motor.
bool getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getControlMode(int j, int *mode) override
Get the current control mode.
bool getRefPositions(double *refs) override
Get the last position reference for all axes.
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 setNominalCurrent(int m, const double val) override
bool getMotorEncoderTimed(int m, double *v, double *t) override
Read the instantaneous position of a motor encoder.
bool getRefCurrents(double *currs) override
Get the reference value of the currents for all motors.
bool close() override
Close the device driver by deallocating all resources and closing ports.
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool getRemoteVariable(std::string key, yarp::os::Bottle &val) override
ControlBoardRemapper()=default
bool checkMotionDone(int j, bool *flag) override
Check if the current trajectory is terminated.
bool calibrationDone(int j) override
Check if the calibration is terminated, on a particular 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 setPWMLimit(int m, const double val) override
bool getTemperatureLimit(int m, double *val) override
Retreives the current temperature limit for a specific motor.
ControlBoardRemapper & operator=(const ControlBoardRemapper &)=delete
bool getAxes(int *ax) override
Get the number of controlled axes.
bool setPidOffset(const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
Set offset value for a given controller.
bool setEncoder(int j, double val) override
Set the value of the encoder for a given joint.
bool setRefAcceleration(int j, double acc) override
Set reference acceleration for a joint.
bool getPid(const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *p) override
Get current pid value for a specific joint.
bool getImpedanceOffset(int j, double *offset) override
Get current force Offset for a specific joint.
bool getEncoderSpeed(int j, double *sp) override
Read the istantaneous speed of an axis.
bool getRefSpeed(int j, double *ref) override
Get reference speed for a joint.
bool resetEncoder(int j) override
Reset encoder, single joint.
bool getDutyCycles(double *vals) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool getEncoderAcceleration(int j, double *acc) override
Read the instantaneous acceleration of an axis.
bool setControlModes(const int n_joints, const int *joints, int *modes) override
Set the current control mode for a subset of axes.
bool getEncoderTimed(int j, double *v, double *t) override
Read the instantaneous acceleration of all axes.
bool getImpedance(int j, double *stiff, double *damp) override
Get current impedance gains (stiffness,damping,offset) for a specific joint.
bool getEncoders(double *encs) override
Read the position of all axes.
bool getRefPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
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 limi...
bool getEncoder(int j, double *v) override
Read the value of an encoder.
bool getMotorEncoder(int m, double *v) override
Read the value of a motor encoder.
bool getTorqueRanges(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
bool getMotorEncodersTimed(double *encs, double *t) override
Read the instantaneous position of all motor encoders.
bool setRefTorque(int j, double t) override
Set the reference value of the torque for a given joint.
bool getNumberOfMotors(int *num) override
Retrieves the number of controlled motors from the current physical interface.
bool disableAmp(int j) override
Disable the amplifier on a specific joint.
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 getPeakCurrent(int m, double *val) override
bool setGearboxRatio(int m, const double val) override
Set the gearbox ratio for a specific motor.
bool quitCalibrate() override
quitCalibrate: interrupt the calibration procedure
bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override
Start calibration, this method is very often platform specific.
bool getAxisName(int j, std::string &name) override
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
bool getRefTorques(double *refs) override
Get the reference value of the torque for all joints.
bool getPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool isPidEnabled(const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid.
bool getRefVelocity(const int joint, double *vel) override
Get the last reference speed set by velocityMove for single joint.
bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
bool setRefCurrents(const double *currs) override
Set the reference value of the currents for all motors.
bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool open(yarp::os::Searchable &prop) override
Open the device driver.
bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
Set the error limit for the controller on a specifi joint.
bool setMaxCurrent(int j, double v) override
yarp::dev::IRemoteCalibrator * getCalibratorDevice() override
getCalibratorDevice: return the pointer stored with the setCalibratorDevice
bool abortCalibration() override
bool enablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Enable the pid computation for a joint.
bool calibrateWholePart() override
calibrateWholePart: call the procedure for calibrating the whole device
bool getLimits(int j, double *min, double *max) override
Get the software limits for a particular axis.
bool getRefDutyCycles(double *refs) override
Gets the last reference sent using the setRefDutyCycles function.
bool getPidReference(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override
Get the current reference of the pid controller for a specific joint.
bool setRefSpeeds(const double *spds) override
Set reference speed on all joints.
bool getNominalCurrent(int m, double *val) override
bool getRefVelocities(double *vels) override
Get the last reference speed set by velocityMove for all joints.
bool setEncoders(const double *vals) override
Set the value of all encoders.
bool getInteractionMode(int j, yarp::dev::InteractionModeEnum *mode) override
Get the current interaction mode of the robot, values can be stiff or compliant.
bool setMotorEncoder(int m, const double val) override
Set the value of the motor encoder for a given motor.
~ControlBoardRemapper() override=default
bool getPidErrors(const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool getPidError(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool getCurrent(int m, double *curr) override
Get the instantaneous current measurement for a single motor.
bool detachAll() override
Detach the object (you must have first called attach).
bool setPids(const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *ps) override
Set new pid value on multiple axes.
bool parkSingleJoint(int j, bool _wait=true) override
parkSingleJoint(): start the parking procedure for the single joint
bool calibrateSingleJoint(int j) override
calibrateSingleJoint: call the calibration procedure for the single joint
bool getRefTorque(int j, double *t) override
Get the reference value of the torque for a given joint.
bool quitPark() override
quitPark: interrupt the park procedure
bool velocityMove(int j, double v) override
Start motion at a given speed, single joint.
bool getRefDutyCycle(int m, double *ref) override
Gets the last reference sent using the setRefDutyCycle function.
bool getNumberOfMotorEncoders(int *num) override
Get the number of available motor encoders.
bool getPidOutput(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool getMotorEncoderAcceleration(int m, double *acc) override
Read the instantaneous acceleration of a motor encoder.
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...
bool setMotorEncoders(const double *vals) override
Set the value of all motor encoders.
bool getMotorEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all motor encoders.
bool setPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
ControlBoardRemapper(const ControlBoardRemapper &)=delete
bool getTargetPositions(double *refs) override
Get the last position reference for all axes.
bool getPWM(int m, double *val) override
bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override
bool setImpedanceOffset(int j, double offset) override
Set current force Offset for a specific joint.
bool getPidOutputs(const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
bool resetEncoders() override
Reset encoders.
bool setRefDutyCycles(const double *refs) override
Sets the reference dutycycle for all the motors.
yarp::os::Stamp getLastInputStamp() override
Return the time stamp relative to the last acquisition.
bool getDutyCycle(int m, double *val) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool getCurrentRanges(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool setRefTorques(const double *t) override
Set the reference value of the torque for all joints.
bool getLastJointFault(int j, int &fault, std::string &message) override
bool resetMotorEncoders() override
Reset motor encoders.
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 getRefCurrent(int m, double *curr) override
Get the reference value of the current for a single motor.
bool setInteractionMode(int j, yarp::dev::InteractionModeEnum mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
bool getGearboxRatio(int m, double *val) override
Get the gearbox ratio for a specific motor.
bool getVelLimits(int j, double *min, double *max) override
Get the software speed limits for a particular axis.
bool getRefAccelerations(double *accs) override
Get reference acceleration of all joints.
bool enableAmp(int j) override
Enable the amplifier on a specific joint.
ControlBoardRemapper(ControlBoardRemapper &&)=delete
bool positionMove(int j, double ref) override
Set new reference point for a single axis.
bool disablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
bool getTemperatures(double *vals) override
Get temperature of all the motors.
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 ...
bool getCurrentRange(int m, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool getTemperature(int m, double *val) override
Get temperature of a motor.
bool setControlMode(const int j, const int mode) override
Set the current control mode.
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 verbose() const
Return the value of the verbose flag.
bool abortPark() override
bool isCalibratorDevicePresent(bool *isCalib) override
isCalibratorDevicePresent: check if a calibrator device has been set
bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
bool getPowerSupplyVoltage(int m, double *val) override
bool getMotorEncoders(double *encs) override
Read the position of all motor encoders.
bool setPositions(const int n_joints, const int *joints, const double *dpos) override
Set new reference point for all axes.
bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters ¶ms) override
Start calibration, this method is very often platform specific.
bool stop() override
Stop motion, multiple joints.
bool getCurrents(double *currs) override
Get the instantaneous current measurement for all motors.
bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override
bool getPWMLimit(int m, double *val) override
bool getEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all axes.
bool setPeakCurrent(int m, const double val) override
bool homingWholePart() override
homingWholePart: call the homing procedure for a the whole part/device
bool getMotorEncoderSpeed(int m, double *sp) override
Read the istantaneous speed of a motor encoder.
bool homingSingleJoint(int j) override
homingSingleJoint: call the homing procedure for a single joint
bool getRefAcceleration(int j, double *acc) override
Get reference acceleration for a joint.
bool getEncodersTimed(double *encs, double *t) override
Read the instantaneous acceleration of all axes.
bool getRefSpeeds(double *spds) override
Get reference speed of all joints.
bool setRefDutyCycle(int m, double ref) override
Sets the reference dutycycle to a single motor.
bool getMaxCurrent(int j, double *v) override
Returns the maximum electric current allowed for a given motor.
bool setPidReference(const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all motor encoders.
bool getPids(const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
Get current pid value for a specific joint.
bool setPosition(int j, double ref) override
Set new position for a single axis.
bool relativeMove(int j, double delta) override
Set relative position.
Class storing the decomposition of all the axes in the Remapped ControlBoard in the SubControlBoard,...
Interface implemented by all device drivers.
Interface for control devices, amplifier commands.
Interface for getting information about specific axes, if available.
Interface for control devices, calibration commands.
Interface for control devices, commands to get/set position and veloity limits.
Interface for setting control mode in control board.
Interface for control boards implementing current control.
Control board, extend encoder interface with timestamps.
Interface for control boards implementing impedance control.
Interface settings the way the robot interacts with the environment: basic interaction types are Stif...
Interface for getting info about the fault which may occur on a robot.
Control board, encoder interface.
Control board, encoder interface.
Interface for an object that can wrap/attach to to another.
Interface for controlling an axis, by sending directly a PWM reference signal to a motor.
Interface for a generic control board device implementing a PID controller, with scaled arguments.
Interface for a generic control board device implementing position control.
Interface for a generic control board device implementing position control.
IRemoteCalibrator interface is meant to remotize the access of the calibration device in order to all...
IRemoteVariables interface.
Interface for control boards implementing torque control.
Interface for control boards implementing velocity control.
Contains the parameters for a PID.
A simple collection of objects that can be described and transmitted in a portable way.
A class for storing options and configuration information.
A base class for nested structures that can be searched.
An abstraction for a time stamp and/or sequence number.