YARP
Yet Another Robot Platform
ControlBoardRemapper.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #ifndef YARP_DEV_CONTROLBOARDREMAPPER_CONTROLBOARDREMAPPER_H
7 #define YARP_DEV_CONTROLBOARDREMAPPER_CONTROLBOARDREMAPPER_H
8 
9 #include <yarp/os/Network.h>
10 
12 #include <yarp/dev/PolyDriver.h>
15 #include <yarp/os/Semaphore.h>
17 
18 #include <string>
19 #include <vector>
20 
22 
23 #ifdef MSVC
24  #pragma warning(disable:4355)
25 #endif
26 
78  public yarp::dev::IMotor,
88  public yarp::dev::IAxisInfo,
92 private:
93  std::vector<std::string> axesNames;
94  RemappedControlBoards remappedControlBoards;
95 
97  int controlledJoints{0};
98 
100  bool _verb{false};
101 
102  // to open ports and print more detailed debug messages
103  std::string partName;
104 
105  // Buffer data used to simplify implementation of multi joint methods
107 
108  // Buffer data used for full controlboard methods
110 
111  // Buffer data for multiple arbitrary joint methods
112  ControlBoardArbitraryAxesDecomposition selectedJointsBuffers;
113 
118  void setNrOfControlledAxes(const size_t nrOfControlledAxes);
119 
125  bool updateAxesName();
126 
130  void configureBuffers();
131 
132  // Parse device options
133  bool parseOptions(yarp::os::Property &prop);
134 
135  bool usingAxesNamesForAttachAll{false};
136  bool usingNetworksForAttachAll{false};
137 
138  /***
139  * Parse device options if networks option is passed
140  *
141  * This will fill the axesNames and controlledJoints attributes, while it
142  * leaves empty the remappedDevices attribute that will be then
143  * filled only at the attachAll method.
144  */
145  bool parseAxesNames(const yarp::os::Property &prop);
146 
147  /***
148  * Parse device options if networks option is passed
149  *
150  * This will fill the remappedDevices and controlledJoints attributes, while it
151  * leaves empty the axesNames attribute that will be then
152  * filled only at the attachAll method.
153  */
154  bool parseNetworks(const yarp::os::Property &prop);
155 
159  bool attachAllUsingNetworks(const yarp::dev::PolyDriverList &l);
160 
164  bool attachAllUsingAxesNames(const yarp::dev::PolyDriverList &l);
165 
170  bool setControlModeAllAxes(const int cm);
171 
172 
173 public:
174  ControlBoardRemapper() = default;
179  ~ControlBoardRemapper() override = default;
180 
185  bool verbose() const { return _verb; }
186 
191  bool close() override;
192 
193 
199  bool open(yarp::os::Searchable &prop) override;
200 
201  bool detachAll() override;
202 
203  bool attachAll(const yarp::dev::PolyDriverList &l) override;
204 
205  /* IPidControl */
206  bool setPid(const yarp::dev::PidControlTypeEnum& pidtype,int j, const yarp::dev::Pid &p) override;
207 
208  bool setPids(const yarp::dev::PidControlTypeEnum& pidtype,const yarp::dev::Pid *ps) override;
209 
210  bool setPidReference(const yarp::dev::PidControlTypeEnum& pidtype,int j, double ref) override;
211 
212  bool setPidReferences(const yarp::dev::PidControlTypeEnum& pidtype,const double *refs) override;
213 
214  bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype,int j, double limit) override;
215 
216  bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype,const double *limits) override;
217 
218  bool getPidError(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *err) override;
219 
220  bool getPidErrors(const yarp::dev::PidControlTypeEnum& pidtype,double *errs) override;
221 
222  bool getPidOutput(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *out) override;
223 
224  bool getPidOutputs(const yarp::dev::PidControlTypeEnum& pidtype,double *outs) override;
225 
226  bool setPidOffset(const yarp::dev::PidControlTypeEnum& pidtype,int j, double v) override;
227 
228  bool getPid(const yarp::dev::PidControlTypeEnum& pidtype,int j, yarp::dev::Pid *p) override;
229 
230  bool getPids(const yarp::dev::PidControlTypeEnum& pidtype,yarp::dev::Pid *pids) override;
231 
232  bool getPidReference(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *ref) override;
233 
234  bool getPidReferences(const yarp::dev::PidControlTypeEnum& pidtype,double *refs) override;
235 
236  bool getPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *limit) override;
237 
238  bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype,double *limits) override;
239 
240  bool resetPid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
241 
242  bool disablePid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
243 
244  bool enablePid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
245 
246  bool isPidEnabled(const yarp::dev::PidControlTypeEnum& pidtype, int j, bool* enabled) override;
247 
248  /* IPositionControl */
249  bool getAxes(int *ax) override;
250 
251  bool positionMove(int j, double ref) override;
252 
253  bool positionMove(const double *refs) override;
254 
255  bool positionMove(const int n_joints, const int *joints, const double *refs) override;
256 
257  bool getTargetPosition(const int joint, double *ref) override;
258 
259  bool getTargetPositions(double *refs) override;
260 
261  bool getTargetPositions(const int n_joint, const int *joints, double *refs) override;
262 
263  bool relativeMove(int j, double delta) override;
264 
265  bool relativeMove(const double *deltas) override;
266 
267  bool relativeMove(const int n_joints, const int *joints, const double *deltas) override;
268 
269  bool checkMotionDone(int j, bool *flag) override;
270 
271  bool checkMotionDone(bool *flag) override;
272 
273  bool checkMotionDone(const int n_joints, const int *joints, bool *flags) override;
274 
275  bool setRefSpeed(int j, double sp) override;
276 
277  bool setRefSpeeds(const double *spds) override;
278 
279  bool setRefSpeeds(const int n_joints, const int *joints, const double *spds) override;
280 
281  bool setRefAcceleration(int j, double acc) override;
282 
283  bool setRefAccelerations(const double *accs) override;
284 
285  bool setRefAccelerations(const int n_joints, const int *joints, const double *accs) override;
286 
287  bool getRefSpeed(int j, double *ref) override;
288 
289  bool getRefSpeeds(double *spds) override;
290 
291  bool getRefSpeeds(const int n_joints, const int *joints, double *spds) override;
292 
293  bool getRefAcceleration(int j, double *acc) override;
294 
295  bool getRefAccelerations(double *accs) override;
296 
297  bool getRefAccelerations(const int n_joints, const int *joints, double *accs) override;
298 
299  bool stop(int j) override;
300 
301  bool stop() override;
302 
303  bool stop(const int n_joints, const int *joints) override;
304 
305  /* IVelocityControl */
306  bool velocityMove(int j, double v) override;
307 
308  bool velocityMove(const double *v) override;
309 
310  /* IEncoders */
311  bool resetEncoder(int j) override;
312 
313  bool resetEncoders() override;
314 
315  bool setEncoder(int j, double val) override;
316 
317  bool setEncoders(const double *vals) override;
318 
319  bool getEncoder(int j, double *v) override;
320 
321  bool getEncoders(double *encs) override;
322 
323  bool getEncodersTimed(double *encs, double *t) override;
324 
325  bool getEncoderTimed(int j, double *v, double *t) override;
326 
327  bool getEncoderSpeed(int j, double *sp) override;
328 
329  bool getEncoderSpeeds(double *spds) override;
330 
331  bool getEncoderAcceleration(int j, double *acc) override;
332 
333  bool getEncoderAccelerations(double *accs) override;
334 
335  /* IMotorEncoders */
336  bool getNumberOfMotorEncoders(int *num) override;
337 
338  bool resetMotorEncoder(int m) override;
339 
340  bool resetMotorEncoders() override;
341 
342  bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override;
343 
344  bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override;
345 
346  bool setMotorEncoder(int m, const double val) override;
347 
348  bool setMotorEncoders(const double *vals) override;
349 
350  bool getMotorEncoder(int m, double *v) override;
351 
352  bool getMotorEncoders(double *encs) override;
353 
354  bool getMotorEncodersTimed(double *encs, double *t) override;
355 
356  bool getMotorEncoderTimed(int m, double *v, double *t) override;
357 
358  bool getMotorEncoderSpeed(int m, double *sp) override;
359 
360  bool getMotorEncoderSpeeds(double *spds) override;
361 
362  bool getMotorEncoderAcceleration(int m, double *acc) override;
363 
364  bool getMotorEncoderAccelerations(double *accs) override;
365 
366  /* IAmplifierControl */
367  bool enableAmp(int j) override;
368 
369  bool disableAmp(int j) override;
370 
371  bool getAmpStatus(int *st) override;
372 
373  bool getAmpStatus(int j, int *v) override;
374 
375  bool setMaxCurrent(int j, double v) override;
376 
377  bool getMaxCurrent(int j, double *v) override;
378 
379  bool getNominalCurrent(int m, double *val) override;
380 
381  bool setNominalCurrent(int m, const double val) override;
382 
383  bool getPeakCurrent(int m, double *val) override;
384 
385  bool setPeakCurrent(int m, const double val) override;
386 
387  bool getPWM(int m, double *val) override;
388 
389  bool getPWMLimit(int m, double *val) override;
390 
391  bool setPWMLimit(int m, const double val) override;
392 
393  bool getPowerSupplyVoltage(int m, double *val) override;
394 
395  /* IControlLimits */
396  bool setLimits(int j, double min, double max) override;
397 
398  bool getLimits(int j, double *min, double *max) override;
399 
400  bool setVelLimits(int j, double min, double max) override;
401 
402  bool getVelLimits(int j, double *min, double *max) override;
403 
404  /* IRemoteVariables */
405 
406  bool getRemoteVariable(std::string key, yarp::os::Bottle &val) override;
407 
408  bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override;
409 
410  bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override;
411 
412  /* IRemoteCalibrator */
413 
414  bool isCalibratorDevicePresent(bool *isCalib) override;
415 
417 
418  bool calibrateSingleJoint(int j) override;
419 
420  bool calibrateWholePart() override;
421 
422  bool homingSingleJoint(int j) override;
423 
424  bool homingWholePart() override;
425 
426  bool parkSingleJoint(int j, bool _wait = true) override;
427 
428  bool parkWholePart() override;
429 
430  bool quitCalibrate() override;
431 
432  bool quitPark() override;
433 
434  /* IControlCalibration */
435 
436  bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override;
437 
438  bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters &params) override;
439 
440  bool calibrationDone(int j) override;
441 
442  bool abortPark() override;
443 
444  bool abortCalibration() override;
445 
446  /* IMotor */
447  bool getNumberOfMotors(int *num) override;
448 
449  bool getTemperature(int m, double *val) override;
450 
451  bool getTemperatures(double *vals) override;
452 
453  bool getTemperatureLimit(int m, double *val) override;
454 
455  bool setTemperatureLimit(int m, const double val) override;
456 
457  bool getGearboxRatio(int m, double *val) override;
458 
459  bool setGearboxRatio(int m, const double val) override;
460 
461  /* IAxisInfo */
462  bool getAxisName(int j, std::string &name) override;
463 
464  bool getJointType(int j, yarp::dev::JointTypeEnum &type) override;
465 
466  bool getRefTorques(double *refs) override;
467 
468  bool getRefTorque(int j, double *t) override;
469 
470  bool setRefTorques(const double *t) override;
471 
472  bool setRefTorque(int j, double t) override;
473 
474  bool setRefTorques(const int n_joint, const int *joints, const double *t) override;
475 
476  bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override;
477 
478  bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override;
479 
480  bool setImpedance(int j, double stiff, double damp) override;
481 
482  bool setImpedanceOffset(int j, double offset) override;
483 
484  bool getTorque(int j, double *t) override;
485 
486  bool getTorques(double *t) override;
487 
488  bool getTorqueRange(int j, double *min, double *max) override;
489 
490  bool getTorqueRanges(double *min, double *max) override;
491 
492  bool getImpedance(int j, double *stiff, double *damp) override;
493 
494  bool getImpedanceOffset(int j, double *offset) override;
495 
496  bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
497 
498  bool getControlMode(int j, int *mode) override;
499 
500  bool getControlModes(int *modes) override;
501 
502  // IControlMode interface
503  bool getControlModes(const int n_joint, const int *joints, int *modes) override;
504 
505  bool setControlMode(const int j, const int mode) override;
506 
507  bool setControlModes(const int n_joints, const int *joints, int *modes) override;
508 
509  bool setControlModes(int *modes) override;
510 
511  bool setPosition(int j, double ref) override;
512 
513  bool setPositions(const int n_joints, const int *joints, const double *dpos) override;
514 
515  bool setPositions(const double *refs) override;
516 
517  bool getRefPosition(const int joint, double *ref) override;
518 
519  bool getRefPositions(double *refs) override;
520 
521  bool getRefPositions(const int n_joint, const int *joints, double *refs) override;
522 
524 
525  // IVelocityControl interface
526  bool velocityMove(const int n_joints, const int *joints, const double *spds) override;
527 
528  bool getRefVelocity(const int joint, double *vel) override;
529 
530  bool getRefVelocities(double *vels) override;
531 
532  bool getRefVelocities(const int n_joint, const int *joints, double *vels) override;
533 
534  bool getInteractionMode(int j, yarp::dev::InteractionModeEnum *mode) override;
535 
536  bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override;
537 
539 
540  bool setInteractionMode(int j, yarp::dev::InteractionModeEnum mode) override;
541 
542  bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override;
543 
545 
546  // IPWMControl
547  bool setRefDutyCycle(int m, double ref) override;
548 
549  bool setRefDutyCycles(const double *refs) override;
550 
551  bool getRefDutyCycle(int m, double *ref) override;
552 
553  bool getRefDutyCycles(double *refs) override;
554 
555  bool getDutyCycle(int m, double *val) override;
556 
557  bool getDutyCycles(double *vals) override;
558 
559  // ICurrentControl
560  bool getCurrent(int m, double *curr) override;
561 
562  bool getCurrents(double *currs) override;
563 
564  bool getCurrentRange(int m, double *min, double *max) override;
565 
566  bool getCurrentRanges(double *min, double *max) override;
567 
568  bool setRefCurrents(const double *currs) override;
569 
570  bool setRefCurrent(int m, double curr) override;
571 
572  bool setRefCurrents(const int n_motor, const int *motors, const double *currs) override;
573 
574  bool getRefCurrents(double *currs) override;
575 
576  bool getRefCurrent(int m, double *curr) override;
577 };
578 
579 #endif // YARP_DEV_CONTROLBOARDREMAPPER_CONTROLBOARDREMAPPER_H
define control board standard interfaces
float t
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.
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.
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 axes 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 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
ControlBoardRemapper & operator=(const ControlBoardRemapper &)=delete
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
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.
ControlBoardRemapper & operator=(ControlBoardRemapper &&)=delete
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 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 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 &params) override
Start calibration, this method is very often platform specific.
bool stop() override
Stop motion, multiple joints.
bool getCurrents(double *currs) override
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.
Definition: DeviceDriver.h:35
Interface for control devices, amplifier commands.
Interface for getting information about specific axes, if available.
Definition: IAxisInfo.h:40
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.
Definition: IControlMode.h:25
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.
Definition: IMotor.h:96
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.
Definition: IPWMControl.h:25
Interface for a generic control board device implementing a PID controller, with scaled arguments.
Definition: IPidControl.h:208
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.
Definition: Bottle.h:74
A class for storing options and configuration information.
Definition: Property.h:34
A base class for nested structures that can be searched.
Definition: Searchable.h:66
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
PidControlTypeEnum
Definition: PidEnums.h:18