YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
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,
93private:
94 std::vector<std::string> axesNames;
95 RemappedControlBoards remappedControlBoards;
96
98 int controlledJoints{0};
99
101 bool _verb{false};
102
103 // to open ports and print more detailed debug messages
104 std::string partName;
105
106 // Buffer data used to simplify implementation of multi joint methods
108
109 // Buffer data used for full controlboard methods
111
112 // Buffer data for multiple arbitrary joint methods
113 ControlBoardArbitraryAxesDecomposition selectedJointsBuffers;
114
119 void setNrOfControlledAxes(const size_t nrOfControlledAxes);
120
126 bool updateAxesName();
127
131 void configureBuffers();
132
133 // Parse device options
134 bool parseOptions(yarp::os::Property &prop);
135
136 bool usingAxesNamesForAttachAll{false};
137 bool usingNetworksForAttachAll{false};
138
139 /***
140 * Parse device options if networks option is passed
141 *
142 * This will fill the axesNames and controlledJoints attributes, while it
143 * leaves empty the remappedDevices attribute that will be then
144 * filled only at the attachAll method.
145 */
146 bool parseAxesNames(const yarp::os::Property &prop);
147
148 /***
149 * Parse device options if networks option is passed
150 *
151 * This will fill the remappedDevices and controlledJoints attributes, while it
152 * leaves empty the axesNames attribute that will be then
153 * filled only at the attachAll method.
154 */
155 bool parseNetworks(const yarp::os::Property &prop);
156
160 bool attachAllUsingNetworks(const yarp::dev::PolyDriverList &l);
161
165 bool attachAllUsingAxesNames(const yarp::dev::PolyDriverList &l);
166
171 bool setControlModeAllAxes(const int cm);
172
173
174public:
180 ~ControlBoardRemapper() override = default;
181
186 bool verbose() const { return _verb; }
187
192 bool close() override;
193
194
200 bool open(yarp::os::Searchable &prop) override;
201
202 bool detachAll() override;
203
204 bool attachAll(const yarp::dev::PolyDriverList &l) override;
205
206 /* IPidControl */
207 bool setPid(const yarp::dev::PidControlTypeEnum& pidtype,int j, const yarp::dev::Pid &p) override;
208
209 bool setPids(const yarp::dev::PidControlTypeEnum& pidtype,const yarp::dev::Pid *ps) override;
210
211 bool setPidReference(const yarp::dev::PidControlTypeEnum& pidtype,int j, double ref) override;
212
213 bool setPidReferences(const yarp::dev::PidControlTypeEnum& pidtype,const double *refs) override;
214
215 bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype,int j, double limit) override;
216
217 bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype,const double *limits) override;
218
219 bool getPidError(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *err) override;
220
221 bool getPidErrors(const yarp::dev::PidControlTypeEnum& pidtype,double *errs) override;
222
223 bool getPidOutput(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *out) override;
224
225 bool getPidOutputs(const yarp::dev::PidControlTypeEnum& pidtype,double *outs) override;
226
227 bool setPidOffset(const yarp::dev::PidControlTypeEnum& pidtype,int j, double v) override;
228
229 bool getPid(const yarp::dev::PidControlTypeEnum& pidtype,int j, yarp::dev::Pid *p) override;
230
231 bool getPids(const yarp::dev::PidControlTypeEnum& pidtype,yarp::dev::Pid *pids) override;
232
233 bool getPidReference(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *ref) override;
234
235 bool getPidReferences(const yarp::dev::PidControlTypeEnum& pidtype,double *refs) override;
236
237 bool getPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *limit) override;
238
239 bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype,double *limits) override;
240
241 bool resetPid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
242
243 bool disablePid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
244
245 bool enablePid(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
246
247 bool isPidEnabled(const yarp::dev::PidControlTypeEnum& pidtype, int j, bool* enabled) override;
248
249 /* IPositionControl */
250 bool getAxes(int *ax) override;
251
252 bool positionMove(int j, double ref) override;
253
254 bool positionMove(const double *refs) override;
255
256 bool positionMove(const int n_joints, const int *joints, const double *refs) override;
257
258 bool getTargetPosition(const int joint, double *ref) override;
259
260 bool getTargetPositions(double *refs) override;
261
262 bool getTargetPositions(const int n_joint, const int *joints, double *refs) override;
263
264 bool relativeMove(int j, double delta) override;
265
266 bool relativeMove(const double *deltas) override;
267
268 bool relativeMove(const int n_joints, const int *joints, const double *deltas) override;
269
270 bool checkMotionDone(int j, bool *flag) override;
271
272 bool checkMotionDone(bool *flag) override;
273
274 bool checkMotionDone(const int n_joints, const int *joints, bool *flags) override;
275
276 bool setRefSpeed(int j, double sp) override;
277
278 bool setRefSpeeds(const double *spds) override;
279
280 bool setRefSpeeds(const int n_joints, const int *joints, const double *spds) override;
281
282 bool setRefAcceleration(int j, double acc) override;
283
284 bool setRefAccelerations(const double *accs) override;
285
286 bool setRefAccelerations(const int n_joints, const int *joints, const double *accs) override;
287
288 bool getRefSpeed(int j, double *ref) override;
289
290 bool getRefSpeeds(double *spds) override;
291
292 bool getRefSpeeds(const int n_joints, const int *joints, double *spds) override;
293
294 bool getRefAcceleration(int j, double *acc) override;
295
296 bool getRefAccelerations(double *accs) override;
297
298 bool getRefAccelerations(const int n_joints, const int *joints, double *accs) override;
299
300 bool stop(int j) override;
301
302 bool stop() override;
303
304 bool stop(const int n_joints, const int *joints) override;
305
306 /* IJointFault */
307
308 bool getLastJointFault(int j, int& fault, std::string& message) override;
309
310 /* IVelocityControl */
311 bool velocityMove(int j, double v) override;
312
313 bool velocityMove(const double *v) override;
314
315 /* IEncoders */
316 bool resetEncoder(int j) override;
317
318 bool resetEncoders() override;
319
320 bool setEncoder(int j, double val) override;
321
322 bool setEncoders(const double *vals) override;
323
324 bool getEncoder(int j, double *v) override;
325
326 bool getEncoders(double *encs) override;
327
328 bool getEncodersTimed(double *encs, double *t) override;
329
330 bool getEncoderTimed(int j, double *v, double *t) override;
331
332 bool getEncoderSpeed(int j, double *sp) override;
333
334 bool getEncoderSpeeds(double *spds) override;
335
336 bool getEncoderAcceleration(int j, double *acc) override;
337
338 bool getEncoderAccelerations(double *accs) override;
339
340 /* IMotorEncoders */
341 bool getNumberOfMotorEncoders(int *num) override;
342
343 bool resetMotorEncoder(int m) override;
344
345 bool resetMotorEncoders() override;
346
347 bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override;
348
349 bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override;
350
351 bool setMotorEncoder(int m, const double val) override;
352
353 bool setMotorEncoders(const double *vals) override;
354
355 bool getMotorEncoder(int m, double *v) override;
356
357 bool getMotorEncoders(double *encs) override;
358
359 bool getMotorEncodersTimed(double *encs, double *t) override;
360
361 bool getMotorEncoderTimed(int m, double *v, double *t) override;
362
363 bool getMotorEncoderSpeed(int m, double *sp) override;
364
365 bool getMotorEncoderSpeeds(double *spds) override;
366
367 bool getMotorEncoderAcceleration(int m, double *acc) override;
368
369 bool getMotorEncoderAccelerations(double *accs) override;
370
371 /* IAmplifierControl */
372 bool enableAmp(int j) override;
373
374 bool disableAmp(int j) override;
375
376 bool getAmpStatus(int *st) override;
377
378 bool getAmpStatus(int j, int *v) override;
379
380 bool setMaxCurrent(int j, double v) override;
381
382 bool getMaxCurrent(int j, double *v) override;
383
384 bool getNominalCurrent(int m, double *val) override;
385
386 bool setNominalCurrent(int m, const double val) override;
387
388 bool getPeakCurrent(int m, double *val) override;
389
390 bool setPeakCurrent(int m, const double val) override;
391
392 bool getPWM(int m, double *val) override;
393
394 bool getPWMLimit(int m, double *val) override;
395
396 bool setPWMLimit(int m, const double val) override;
397
398 bool getPowerSupplyVoltage(int m, double *val) override;
399
400 /* IControlLimits */
401 bool setLimits(int j, double min, double max) override;
402
403 bool getLimits(int j, double *min, double *max) override;
404
405 bool setVelLimits(int j, double min, double max) override;
406
407 bool getVelLimits(int j, double *min, double *max) override;
408
409 /* IRemoteVariables */
410
411 bool getRemoteVariable(std::string key, yarp::os::Bottle &val) override;
412
413 bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override;
414
415 bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override;
416
417 /* IRemoteCalibrator */
418
419 bool isCalibratorDevicePresent(bool *isCalib) override;
420
422
423 bool calibrateSingleJoint(int j) override;
424
425 bool calibrateWholePart() override;
426
427 bool homingSingleJoint(int j) override;
428
429 bool homingWholePart() override;
430
431 bool parkSingleJoint(int j, bool _wait = true) override;
432
433 bool parkWholePart() override;
434
435 bool quitCalibrate() override;
436
437 bool quitPark() override;
438
439 /* IControlCalibration */
440
441 bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override;
442
443 bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters &params) override;
444
445 bool calibrationDone(int j) override;
446
447 bool abortPark() override;
448
449 bool abortCalibration() override;
450
451 /* IMotor */
452 bool getNumberOfMotors(int *num) override;
453
454 bool getTemperature(int m, double *val) override;
455
456 bool getTemperatures(double *vals) override;
457
458 bool getTemperatureLimit(int m, double *val) override;
459
460 bool setTemperatureLimit(int m, const double val) override;
461
462 bool getGearboxRatio(int m, double *val) override;
463
464 bool setGearboxRatio(int m, const double val) override;
465
466 /* IAxisInfo */
467 bool getAxisName(int j, std::string &name) override;
468
469 bool getJointType(int j, yarp::dev::JointTypeEnum &type) override;
470
471 bool getRefTorques(double *refs) override;
472
473 bool getRefTorque(int j, double *t) override;
474
475 bool setRefTorques(const double *t) override;
476
477 bool setRefTorque(int j, double t) override;
478
479 bool setRefTorques(const int n_joint, const int *joints, const double *t) override;
480
481 bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override;
482
483 bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override;
484
485 bool setImpedance(int j, double stiff, double damp) override;
486
487 bool setImpedanceOffset(int j, double offset) override;
488
489 bool getTorque(int j, double *t) override;
490
491 bool getTorques(double *t) override;
492
493 bool getTorqueRange(int j, double *min, double *max) override;
494
495 bool getTorqueRanges(double *min, double *max) override;
496
497 bool getImpedance(int j, double *stiff, double *damp) override;
498
499 bool getImpedanceOffset(int j, double *offset) override;
500
501 bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
502
503 bool getControlMode(int j, int *mode) override;
504
505 bool getControlModes(int *modes) override;
506
507 // IControlMode interface
508 bool getControlModes(const int n_joint, const int *joints, int *modes) override;
509
510 bool setControlMode(const int j, const int mode) override;
511
512 bool setControlModes(const int n_joints, const int *joints, int *modes) override;
513
514 bool setControlModes(int *modes) override;
515
516 bool setPosition(int j, double ref) override;
517
518 bool setPositions(const int n_joints, const int *joints, const double *dpos) override;
519
520 bool setPositions(const double *refs) override;
521
522 bool getRefPosition(const int joint, double *ref) override;
523
524 bool getRefPositions(double *refs) override;
525
526 bool getRefPositions(const int n_joint, const int *joints, double *refs) override;
527
529
530 // IVelocityControl interface
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
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 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 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
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.
Definition IAxisInfo.h:36
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.
Definition IJointFault.h:23
Control board, encoder interface.
Control board, encoder interface.
Definition IMotor.h:94
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:23
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.
Definition Bottle.h:64
A class for storing options and configuration information.
Definition Property.h:33
A base class for nested structures that can be searched.
Definition Searchable.h:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
PidControlTypeEnum
Definition PidEnums.h:15