9 #ifndef YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H
10 #define YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H
51 #pragma warning(disable:4355)
54 #define PROTOCOL_VERSION_MAJOR 1
55 #define PROTOCOL_VERSION_MINOR 9
56 #define PROTOCOL_VERSION_TWEAK 0
103 modes [i] =
modes[i-1] + _maxJointsNumForDevice;
251 std::string rootName;
263 std::mutex timeMutex;
272 std::vector<std::string> jointNames;
273 std::string rosNodeName;
274 std::string rosTopicName;
286 std::mutex rpcDataMutex;
289 std::string partName;
291 int controlledJoints;
298 bool updateAxisName();
300 bool initialize_ROS();
302 void cleanup_yarpPorts();
314 inline void printError(std::string func_name, std::string info,
bool result)
324 void calculateMaxNumOfJointsInDevices();
353 bool close()
override;
409 bool getAxes(
int *ax)
override;
430 bool positionMove(
const int n_joints,
const int *joints,
const double *refs)
override;
484 bool relativeMove(
const int n_joints,
const int *joints,
const double *deltas)
override;
507 bool checkMotionDone(
const int n_joints,
const int *joints,
bool *flags)
override;
530 bool setRefSpeeds(
const int n_joints,
const int *joints,
const double *spds)
override;
553 bool setRefAccelerations(
const int n_joints,
const int *joints,
const double *accs)
override;
576 bool getRefSpeeds(
const int n_joints,
const int *joints,
double *spds)
override;
605 bool stop(
int j)
override;
611 bool stop()
override;
618 bool stop(
const int n_joints,
const int *joints)
override;
927 bool getPWM(
int m,
double* val)
override;
943 bool setPWMLimit(
int m,
const double val)
override;
962 bool setLimits(
int j,
double min,
double max)
override;
971 bool getLimits(
int j,
double *min,
double *max)
override;
981 bool setVelLimits(
int j,
double min,
double max)
override;
990 bool getVelLimits(
int j,
double *min,
double *max)
override;
1092 bool getAxisName(
int j, std::string& name)
override;
1104 bool setRefTorques(
const int n_joint,
const int *joints,
const double *
t)
override;
1110 bool setImpedance(
int j,
double stiff,
double damp)
override;
1122 bool getImpedance(
int j,
double* stiff,
double* damp)
override;
1126 bool getCurrentImpedanceLimit(
int j,
double *min_stiff,
double *max_stiff,
double *min_damp,
double *max_damp)
override;
1133 bool getControlModes(
const int n_joint,
const int *joints,
int *modes)
override;
1137 bool setControlModes(
const int n_joints,
const int *joints,
int *modes)
override;
1145 bool setPositions(
const int n_joints,
const int *joints,
const double *dpos)
override;
1180 bool getRefPositions(
const int n_joint,
const int *joints,
double *refs)
override;
1187 bool velocityMove(
const int n_joints,
const int *joints,
const double *spds)
override;
1193 bool getRefVelocities(
const int n_joint,
const int* joints,
double* vels)
override;
1229 bool setRefCurrents(
const int n_joint,
const int *joints,
const double *
t)
override;
define control board standard interfaces
contains the definition of a Vector type
bool getRefDutyCycle(int j, double *v) override
Gets the last reference sent using the setRefDutyCycle function.
bool getImpedance(int j, double *stiff, double *damp) override
Get current impedance gains (stiffness,damping,offset) for a specific joint.
bool getControlMode(int j, int *mode) override
Get the current control mode.
bool getTargetPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool setControlModes(const int n_joints, const int *joints, int *modes) override
Set the current control mode for a subset of axes.
bool open(yarp::os::Searchable &prop) override
Open the device driver.
bool getTemperatures(double *vals) override
Get temperature of all the motors.
bool abortPark() override
bool setEncoders(const double *vals) override
Set the value of all encoders.
bool setGearboxRatio(int m, const double val) override
Set the gearbox ratio for a specific motor.
bool setControlMode(const int j, const int mode) override
Set the current control mode.
bool getPidOutput(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool enableAmp(int j) override
Enable the amplifier on a specific joint.
bool getCurrentRanges(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool getPWMLimit(int m, double *val) override
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool getLimits(int j, double *min, double *max) override
Get the software limits for a particular axis.
bool getAxes(int *ax) override
Get the number of controlled axes.
bool detachAll() override
Detach the object (you must have first called attach).
bool getNominalCurrent(int m, double *val) override
bool setRefCurrent(int j, double t) override
Set the reference value of the current for a single motor.
bool getEncoderTimed(int j, double *v, double *t) override
Read the instantaneous acceleration of all axes.
bool getMotorEncoderAccelerations(double *accs) override
Read the istantaneous acceleration of all axes.
bool getCurrentRange(int j, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool getEncoderAccelerations(double *accs) override
Read the istantaneous acceleration of 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 disablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
bool verbose() const
Return the value of the verbose flag.
bool setRefCurrents(const double *t) override
Set the reference value of the currents for all motors.
bool getCurrents(double *vals) override
Read the electric current going to all motors.
bool getMotorEncoders(double *encs) override
Read the position of all axes.
bool getRefVelocity(const int joint, double *vel) override
Get the last reference speed set by velocityMove for single joint.
bool setPidReference(const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool getPowerSupplyVoltage(int m, double *val) override
bool setRefTorque(int j, double t) override
Set the reference value of the torque for a given joint.
bool setTemperatureLimit(int m, const double val) override
Set the temperature limit for a specific motor.
bool setRefDutyCycles(const double *v) override
Sets the reference dutycycle for all the motors.
bool getTemperatureLimit(int m, double *val) override
Retreives the current temperature limit for a specific motor.
bool relativeMove(int j, double delta) override
Set relative position.
bool getTemperature(int m, double *val) override
Get temperature of a motor.
bool getRefCurrents(double *t) override
Get the reference value of the currents for all motors.
bool setPids(const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *ps) override
Set new pid value on multiple axes.
bool setRefTorques(const double *t) override
Set the reference value of the torque for all joints.
bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override
Start calibration, this method is very often platform specific.
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getPids(const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
Get current pid value for a specific joint.
bool getRefVelocities(double *vels) override
Get the last reference speed set by velocityMove for all joints.
bool positionMove(int j, double ref) override
Set new reference point for a single axis.
bool getMotorEncoder(int m, double *v) override
Read the value of an encoder.
bool resetMotorEncoder(int m) override
Reset encoder, single joint.
bool getMaxCurrent(int j, double *v) override
Returns the maximum electric current allowed for a given motor.
bool setEncoder(int j, double val) override
Set the value of the encoder for a given joint.
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 getRefPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool abortCalibration() override
bool setRefDutyCycle(int j, double v) override
Sets the reference dutycycle to a single motor.
bool getRefPositions(double *refs) override
Get the last position reference for all axes.
bool getRefTorque(int j, double *t) override
Get the reference value of the torque for a given joint.
bool getDutyCycles(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool setMotorEncoders(const double *vals) override
Set the value of all encoders.
bool getPidError(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
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 setPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
bool setMaxCurrent(int j, double v) override
Set the maximum electric current going to a given motor.
bool getAmpStatus(int *st) override
Get the status of the amplifiers, coded in a 32 bits integer for each amplifier (at the moment contai...
bool getRefCurrent(int j, double *t) override
Get the reference value of the current for a single motor.
bool setPWMLimit(int m, const double val) override
bool getMotorEncoderAcceleration(int m, double *acc) override
Read the instantaneous acceleration of an axis.
yarp::os::Stamp getLastInputStamp() override
Return the time stamp relative to the last acquisition.
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
bool getTorqueRange(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool calibrateWholePart() override
calibrateWholePart: call the procedure for calibrating the whole device
bool velocityMove(int j, double v) override
Set new reference speed for a single axis.
bool quitCalibrate() override
quitCalibrate: interrupt the calibration procedure
ControlBoardWrapper & operator=(const ControlBoardWrapper &)=delete
bool getRefDutyCycles(double *v) override
Gets the last reference sent using the setRefDutyCycles function.
bool getEncodersTimed(double *encs, double *t) override
Read the instantaneous acceleration of all axes.
bool getDutyCycle(int j, double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool stop() override
Stop motion, multiple joints.
bool resetMotorEncoders() override
Reset 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 enablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Enable the pid computation for a joint.
bool getTargetPositions(double *refs) override
Get the last position reference for all axes.
bool getEncoderSpeed(int j, double *sp) override
Read the istantaneous speed of an axis.
bool getMotorEncoderSpeed(int m, double *sp) override
Read the istantaneous speed of an axis.
bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
bool getNumberOfMotors(int *num) override
Retrieves the number of controlled axes from the current physical interface.
bool setPeakCurrent(int m, const double val) override
bool setNominalCurrent(int m, const double val) override
bool setPidOffset(const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
Set offset value for a given controller.
bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override
gets number of counts per revolution for motor encoder m.
bool setPid(const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override
Set new pid value for a joint axis.
yarp::dev::IRemoteCalibrator * getCalibratorDevice() override
getCalibratorDevice: return the pointer stored with the setCalibratorDevice
bool disableAmp(int j) override
Disable the amplifier on a specific joint.
bool getPidOutputs(const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool parkSingleJoint(int j, bool _wait=true) override
parkSingleJoint(): start the parking procedure for the single joint
bool getImpedanceOffset(int j, double *offset) override
Get current force Offset for a specific joint.
bool setPosition(int j, double ref) override
Set new position for a single axis.
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 getRemoteVariable(std::string key, yarp::os::Bottle &val) override
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 getNumberOfMotorEncoders(int *num) override
Get the number of available 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 calibrateSingleJoint(int j) override
calibrateSingleJoint: call the calibration procedure for the single joint
bool setRefSpeeds(const double *spds) override
Set reference speed on all joints.
bool getEncoders(double *encs) override
Read the position of all axes.
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 calibrationDone(int j) override
Check whether the calibration has been completed.
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 getEncoder(int j, double *v) override
Read the value of an encoder.
bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
bool checkMotionDone(int j, bool *flag) override
Check if the current trajectory is terminated.
bool setImpedanceOffset(int j, double offset) override
Set current force Offset for a specific joint.
bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override
bool setRefAccelerations(const double *accs) override
Set reference acceleration on all joints.
bool homingWholePart() override
homingWholePart: call the homing procedure for a the whole part/device
bool getRefSpeed(int j, double *ref) override
Get reference speed 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 isCalibratorDevicePresent(bool *isCalib) override
isCalibratorDevicePresent: check if a calibrator device has been set
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 getPidErrors(const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool setMotorEncoder(int m, const double val) override
Set the value of the encoder for a given joint.
ControlBoardWrapper & operator=(ControlBoardWrapper &&)=delete
bool setInteractionMode(int j, yarp::dev::InteractionModeEnum mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
bool getPWM(int m, double *val) override
bool getTorqueRanges(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
ControlBoardWrapper(const ControlBoardWrapper &)=delete
bool getEncoderAcceleration(int j, double *acc) override
Read the instantaneous acceleration of an axis.
~ControlBoardWrapper() override
bool getRefSpeeds(double *spds) override
Get reference speed of all joints.
bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
Set the error limit for the controller on a specifi joint.
bool close() override
Close the device driver by deallocating all resources and closing ports.
bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool resetEncoders() override
Reset encoders.
bool isPidEnabled(const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid.
bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters ¶ms) override
Start calibration, this method is very often platform specific.
bool getRefAccelerations(double *accs) override
Get reference acceleration of all joints.
bool resetEncoder(int j) override
Reset encoder, single joint.
bool getCurrent(int j, double *val) override
Read the electric current going to a given motor.
bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
ControlBoardWrapper(ControlBoardWrapper &&)=delete
bool getMotorEncoderTimed(int m, double *v, double *t) override
Read the instantaneous position of a motor encoder.
bool setRefAcceleration(int j, double acc) override
Set reference acceleration for a 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 getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
bool getPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override
bool parkWholePart() override
parkWholePart: start the parking procedure for the whole part
bool getPeakCurrent(int m, double *val) override
bool getGearboxRatio(int m, double *val) override
Get the gearbox ratio for a specific motor.
bool quitPark() override
quitPark: interrupt the park procedure
bool getAxisName(int j, std::string &name) override
bool setVelLimits(int j, double min, double max) override
Set the software velocity limits for a particular axis, the behavior of the control card when these l...
void run() override
The thread main loop deals with writing on ports here.
bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
bool getVelLimits(int j, double *min, double *max) override
Get the software velocity limits for a particular axis.
bool getRefTorques(double *refs) override
Get the reference value of the torque for all joints.
bool setPositions(const int n_joints, const int *joints, const double *dpos) override
Set new reference point for all axes.
bool getMotorEncodersTimed(double *encs, double *t) override
Read the instantaneous position of all motor encoders.
void resize(int _deviceNum, int _maxJointsNumForDevice, WrappedDevice *_device)
int * subdev_jointsVectorLen
int maxJointsNumForDevice
SubDevice ** subdevices_p
Helper object for parsing RPC port messages.
Callback implementation after buffered input.
SubDevice * getSubdevice(unsigned int i)
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...
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 container for a device driver.
A simple collection of objects that can be described and transmitted in a portable way.
An abstraction for a periodic thread.
A mini-server for network communication.
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.
std::uint32_t NetUint32
Definition of the NetUint32 type.