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