YARP
Yet Another Robot Platform
fakeMotionControl.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_DEVICE_FAKE_MOTIONCONTROL
7#define YARP_DEVICE_FAKE_MOTIONCONTROL
8
9#include <yarp/os/Time.h>
10#include <yarp/os/Bottle.h>
11#include <yarp/sig/Vector.h>
21
22#include <mutex>
23
24
26{
27 double min_stiff;
28 double max_stiff;
29 double min_damp;
30 double max_damp;
31 double param_a;
32 double param_b;
33 double param_c;
34
35public:
37 {
38 min_stiff=0;
39 max_stiff=0;
40 min_damp=0;
41 max_damp=0;
42 param_a=0;
43 param_b=0;
44 param_c=0;
45 }
46
48 {
49 return min_stiff;
50 }
52 {
53 return max_stiff;
54 }
55 double get_min_damp()
56 {
57 return min_damp;
58 }
59 double get_max_damp()
60 {
61 return max_damp;
62 }
63};
64
66{
67 double stiffness;
68 double damping;
71};
72
88// public yarp::dev::DeviceResponder,
128{
129private:
130 enum VerboseLevel
131 {
132 MUTE = 0, // only errors that prevent device from working
133 QUIET = 1, // adds errors that can cause malfunctioning
134 DEFAULT = 2, // adds warnings // DEFAULT // show noisy messages about back-compatible changes
135 CHATTY = 3, // adds info messages
136 VERBOSE = 4, // adds debug messages
137 VERY_VERBOSE = 5, // adds trace of events (shows thread running and catch if they get stuck)
138 VERY_VERY_VERBOSE = 6 // adds messages printed every cycle, so too much verbose for usage, only for deep debugging
139 };
140
141 std::recursive_mutex _mutex;
142 int _njoints;
143 int *_axisMap;
144 double *_angleToEncoder;
145 double *_encodersStamp;
146 double *_ampsToSensor;
147 double *_dutycycleToPWM;
148 float *_DEPRECATED_encoderconversionfactor;
149 float *_DEPRECATED_encoderconversionoffset;
150// uint8_t *_jointEncoderType; /** joint encoder type*/
151 int *_jointEncoderRes;
152 int *_rotorEncoderRes;
153// uint8_t *_rotorEncoderType; /** rotor encoder type*/
154 double *_gearbox;
155 bool *_hasHallSensor;
156 bool *_hasTempSensor;
157 bool *_hasRotorEncoder;
158 bool *_hasRotorEncoderIndex;
159 int *_rotorIndexOffset;
160 int *_motorPoles;
161 double *_rotorlimits_max;
162 double *_rotorlimits_min;
163 yarp::dev::Pid *_ppids;
164 yarp::dev::Pid *_tpids;
165 yarp::dev::Pid *_cpids;
166 yarp::dev::Pid *_vpids;
167 bool *_ppids_ena;
168 bool *_tpids_ena;
169 bool *_cpids_ena;
170 bool *_vpids_ena;
171 double *_ppids_lim;
172 double *_tpids_lim;
173 double *_cpids_lim;
174 double *_vpids_lim;
175 double *_ppids_ref;
176 double *_tpids_ref;
177 double *_cpids_ref;
178 double *_vpids_ref;
179
180 std::string *_axisName;
181 yarp::dev::JointTypeEnum *_jointType;
182// ImpedanceLimits *_impedance_limits; /** impedance limits */
183 double *_limitsMin;
184 double *_limitsMax;
185 double *_kinematic_mj;
186 //double *_currentLimits; /** current limits */
187// MotorCurrentLimits *_currentLimits;
188 double *_maxJntCmdVelocity;
189 double *_maxMotorVelocity;
190 int *_velocityShifts;
191 int *_velocityTimeout;
192 double *_kbemf;
193 double *_ktau;
194 int *_kbemf_scale;
195 int *_ktau_scale;
196 double *_viscousPos;
197 double *_viscousNeg;
198 double *_coulombPos;
199 double *_coulombNeg;
200 int * _filterType;
201 int *_torqueSensorId;
202 int *_torqueSensorChan;
203 double *_maxTorque;
204 double *_newtonsToSensor;
205 bool *checking_motiondone; /* flag telling if I'm already waiting for motion done */
206 double *_last_position_move_time;
207 double *_motorPwmLimits;
208 double *_torques;
210// ImpedanceParameters *_impedance_params; /** impedance parameters */
211
212 bool verbosewhenok;
213 bool useRawEncoderData;
214 bool _pwmIsLimited;
215 bool _torqueControlEnabled;
217 enum torqueControlUnitsType {T_MACHINE_UNITS=0, T_METRIC_UNITS=1};
218 torqueControlUnitsType _torqueControlUnits;
219
220 enum positionControlUnitsType {P_MACHINE_UNITS=0, P_METRIC_UNITS=1};
221 positionControlUnitsType _positionControlUnits;
222
223 // internal stuff
224 int *_controlModes = nullptr;
225 int *_hwfault_code = nullptr;
226 std::string *_hwfault_message = nullptr;
227 int *_interactMode = nullptr;
228 bool *_enabledAmp = nullptr; // Middle step toward a full enabled motor controller. Amp (pwm) plus Pid enable command must be sent in order to get the joint into an active state.
229 bool *_enabledPid = nullptr; // Depends on enabledAmp. When both are set, the joint exits the idle mode and goes into position mode. If one of them is disabled, it falls to idle.
230 bool *_calibrated = nullptr; // Flag to know if the calibrate function has been called for the joint
231 double *_posCtrl_references = nullptr; // used for position control.
232 double *_posDir_references = nullptr; // used for position Direct control.
233 double *_ref_speeds = nullptr; // used for position control.
234 double *_command_speeds = nullptr; // used for velocity control.
235 double *_ref_accs = nullptr; // for velocity control, in position min jerk eq is used.
236 double *_ref_torques = nullptr; // for torque control.
237 double *_ref_currents = nullptr;
238 yarp::sig::Vector current, nominalCurrent, maxCurrent, peakCurrent;
239 yarp::sig::Vector pwm, pwmLimit, refpwm, supplyVoltage,last_velocity_command, last_pwm_command;
240 yarp::sig::Vector pos, dpos, vel, speed, acc, loc, amp;
241 double prev_time;
242 bool opened;
243
244 // debugging
245 VerboseLevel verbose;
246public:
247
250
251 // Device Driver
252 bool open(yarp::os::Searchable &par) override;
253 bool close() override;
254 bool fromConfig(yarp::os::Searchable &config);
255
256 virtual bool initialised();
257
261 bool alloc(int njoints);
262
266 void resizeBuffers();
267
268 bool threadInit() override;
269 void threadRelease() override;
270
272 bool setPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, const yarp::dev::Pid &pid) override;
273 bool setPidsRaw(const yarp::dev::PidControlTypeEnum& pidtype,const yarp::dev::Pid *pids) override;
274 bool setPidReferenceRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double ref) override;
275 bool setPidReferencesRaw(const yarp::dev::PidControlTypeEnum& pidtype,const double *refs) override;
276 bool setPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double limit) override;
277 bool setPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum& pidtype,const double *limits) override;
278 bool getPidErrorRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *err) override;
279 bool getPidErrorsRaw(const yarp::dev::PidControlTypeEnum& pidtype, double *errs) override;
280 bool getPidOutputRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *out) override;
281 bool getPidOutputsRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *outs) override;
282 bool getPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, yarp::dev::Pid *pid) override;
283 bool getPidsRaw(const yarp::dev::PidControlTypeEnum& pidtype, yarp::dev::Pid *pids) override;
284 bool getPidReferenceRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *ref) override;
285 bool getPidReferencesRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *refs) override;
286 bool getPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *limit) override;
287 bool getPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *limits) override;
288 bool resetPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
289 bool disablePidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
290 bool enablePidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
291 bool setPidOffsetRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double v) override;
292 bool isPidEnabledRaw(const yarp::dev::PidControlTypeEnum& pidtype, int j, bool* enabled) override;
293
294 // POSITION CONTROL INTERFACE RAW
295 bool getAxes(int *ax) override;
296 bool positionMoveRaw(int j, double ref) override;
297 bool positionMoveRaw(const double *refs) override;
298 bool relativeMoveRaw(int j, double delta) override;
299 bool relativeMoveRaw(const double *deltas) override;
300 bool checkMotionDoneRaw(bool *flag) override;
301 bool checkMotionDoneRaw(int j, bool *flag) override;
302 bool setRefSpeedRaw(int j, double sp) override;
303 bool setRefSpeedsRaw(const double *spds) override;
304 bool setRefAccelerationRaw(int j, double acc) override;
305 bool setRefAccelerationsRaw(const double *accs) override;
306 bool getRefSpeedRaw(int j, double *ref) override;
307 bool getRefSpeedsRaw(double *spds) override;
308 bool getRefAccelerationRaw(int j, double *acc) override;
309 bool getRefAccelerationsRaw(double *accs) override;
310 bool stopRaw(int j) override;
311 bool stopRaw() override;
312
313 // Position Control2 Interface
314 bool positionMoveRaw(const int n_joint, const int *joints, const double *refs) override;
315 bool relativeMoveRaw(const int n_joint, const int *joints, const double *deltas) override;
316 bool checkMotionDoneRaw(const int n_joint, const int *joints, bool *flags) override;
317 bool setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds) override;
318 bool setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs) override;
319 bool getRefSpeedsRaw(const int n_joint, const int *joints, double *spds) override;
320 bool getRefAccelerationsRaw(const int n_joint, const int *joints, double *accs) override;
321 bool stopRaw(const int n_joint, const int *joints) override;
322 bool getTargetPositionRaw(const int joint, double *ref) override;
323 bool getTargetPositionsRaw(double *refs) override;
324 bool getTargetPositionsRaw(const int n_joint, const int *joints, double *refs) override;
325
326 // Velocity control interface raw
327 bool velocityMoveRaw(int j, double sp) override;
328 bool velocityMoveRaw(const double *sp) override;
329
330 // IJointFault
331 bool getLastJointFaultRaw(int j, int& fault, std::string& message) override;
332
333 // calibration2raw
334 bool setCalibrationParametersRaw(int axis, const yarp::dev::CalibrationParameters& params) override;
335 bool calibrateAxisWithParamsRaw(int axis, unsigned int type, double p1, double p2, double p3) override;
336 bool calibrationDoneRaw(int j) override;
337
338
340
341 // ControlMode
342 bool getControlModeRaw(int j, int *v) override;
343 bool getControlModesRaw(int *v) override;
344
345 // ControlMode 2
346 bool getControlModesRaw(const int n_joint, const int *joints, int *modes) override;
347 bool setControlModeRaw(const int j, const int mode) override;
348 bool setControlModesRaw(const int n_joint, const int *joints, int *modes) override;
349 bool setControlModesRaw(int *modes) override;
350
352 bool resetEncoderRaw(int j) override;
353 bool resetEncodersRaw() override;
354 bool setEncoderRaw(int j, double val) override;
355 bool setEncodersRaw(const double *vals) override;
356 bool getEncoderRaw(int j, double *v) override;
357 bool getEncodersRaw(double *encs) override;
358 bool getEncoderSpeedRaw(int j, double *sp) override;
359 bool getEncoderSpeedsRaw(double *spds) override;
360 bool getEncoderAccelerationRaw(int j, double *spds) override;
361 bool getEncoderAccelerationsRaw(double *accs) override;
363
364 bool getEncodersTimedRaw(double *encs, double *stamps) override;
365 bool getEncoderTimedRaw(int j, double *encs, double *stamp) override;
366
368 bool getNumberOfMotorEncodersRaw(int * num) override;
369 bool resetMotorEncoderRaw(int m) override;
370 bool resetMotorEncodersRaw() override;
371 bool setMotorEncoderRaw(int m, const double val) override;
372 bool setMotorEncodersRaw(const double *vals) override;
373 bool getMotorEncoderRaw(int m, double *v) override;
374 bool getMotorEncodersRaw(double *encs) override;
375 bool getMotorEncoderSpeedRaw(int m, double *sp) override;
376 bool getMotorEncoderSpeedsRaw(double *spds) override;
377 bool getMotorEncoderAccelerationRaw(int m, double *spds) override;
378 bool getMotorEncoderAccelerationsRaw(double *accs) override;
379 bool getMotorEncodersTimedRaw(double *encs, double *stamps) override;
380 bool getMotorEncoderTimedRaw(int m, double *encs, double *stamp) override;\
381 bool getMotorEncoderCountsPerRevolutionRaw(int m, double *v) override;
382 bool setMotorEncoderCountsPerRevolutionRaw(int m, const double cpr) override;
384
386 bool getAxisNameRaw(int axis, std::string& name) override;
387 bool getJointTypeRaw(int axis, yarp::dev::JointTypeEnum& type) override;
389
390 //Internal use, not exposed by YARP (yet)
391 bool getGearboxRatioRaw(int m, double *gearbox) override;
392 virtual bool getRotorEncoderResolutionRaw(int m, double &rotres);
393 virtual bool getJointEncoderResolutionRaw(int m, double &jntres);
394 virtual bool getJointEncoderTypeRaw(int j, int &type);
395 virtual bool getRotorEncoderTypeRaw(int j, int &type);
396 virtual bool getKinematicMJRaw(int j, double &rotres);
397 virtual bool getHasTempSensorsRaw(int j, int& ret);
398 virtual bool getHasHallSensorRaw(int j, int& ret);
399 virtual bool getHasRotorEncoderRaw(int j, int& ret);
400 virtual bool getHasRotorEncoderIndexRaw(int j, int& ret);
401 virtual bool getMotorPolesRaw(int j, int& poles);
402 virtual bool getRotorIndexOffsetRaw(int j, double& rotorOffset);
403 virtual bool getTorqueControlFilterType(int j, int& type);
404
406 bool enableAmpRaw(int j) override;
407 bool disableAmpRaw(int j) override;
408 bool getCurrentsRaw(double *vals) override;
409 bool getCurrentRaw(int j, double *val) override;
410 bool getNominalCurrentRaw(int m, double *val) override;
411 bool setNominalCurrentRaw(int m, const double val) override;
412 bool setMaxCurrentRaw(int j, double val) override;
413 bool getMaxCurrentRaw(int j, double *val) override;
414 bool getPeakCurrentRaw(int m, double *val) override;
415 bool setPeakCurrentRaw(int m, const double val) override;
416 bool getAmpStatusRaw(int *st) override;
417 bool getAmpStatusRaw(int j, int *st) override;
418 bool getPWMRaw(int j, double* val) override;
419 bool getPWMLimitRaw(int j, double* val) override;
420 bool setPWMLimitRaw(int j, const double val) override;
421 bool getPowerSupplyVoltageRaw(int j, double* val) override;
423
424 // Limits
425 bool setLimitsRaw(int axis, double min, double max) override;
426 bool getLimitsRaw(int axis, double *min, double *max) override;
427 // Limits 2
428 bool setVelLimitsRaw(int axis, double min, double max) override;
429 bool getVelLimitsRaw(int axis, double *min, double *max) override;
430
431 // Torque control
432 bool getTorqueRaw(int j, double *t) override;
433 bool getTorquesRaw(double *t) override;
434 bool getTorqueRangeRaw(int j, double *min, double *max) override;
435 bool getTorqueRangesRaw(double *min, double *max) override;
436 bool setRefTorquesRaw(const double *t) override;
437 bool setRefTorqueRaw(int j, double t) override;
438 bool setRefTorquesRaw(const int n_joint, const int *joints, const double *t) override;
439 bool getRefTorquesRaw(double *t) override;
440 bool getRefTorqueRaw(int j, double *t) override;
441 bool getMotorTorqueParamsRaw(int j, yarp::dev::MotorTorqueParameters *params) override;
442 bool setMotorTorqueParamsRaw(int j, const yarp::dev::MotorTorqueParameters params) override;
443// int32_t getRefSpeedInTbl(uint8_t boardNum, int j, eOmeas_position_t pos) override;
444
445 // IVelocityControl interface
446 bool velocityMoveRaw(const int n_joint, const int *joints, const double *spds) override;
447 bool getRefVelocityRaw(const int joint, double *ref) override;
448 bool getRefVelocitiesRaw(double *refs) override;
449 bool getRefVelocitiesRaw(const int n_joint, const int *joints, double *refs) override;
450
451 // Impedance interface
452 bool getImpedanceRaw(int j, double *stiffness, double *damping) override;
453 bool setImpedanceRaw(int j, double stiffness, double damping) override;
454 bool setImpedanceOffsetRaw(int j, double offset) override;
455 bool getImpedanceOffsetRaw(int j, double *offset) override;
456 bool getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
457
458 // PositionDirect Interface
459 bool setPositionRaw(int j, double ref) override;
460 bool setPositionsRaw(const int n_joint, const int *joints, const double *refs) override;
461 bool setPositionsRaw(const double *refs) override;
462 bool getRefPositionRaw(const int joint, double *ref) override;
463 bool getRefPositionsRaw(double *refs) override;
464 bool getRefPositionsRaw(const int n_joint, const int *joints, double *refs) override;
465
466 // InteractionMode interface
467 bool getInteractionModeRaw(int j, yarp::dev::InteractionModeEnum* _mode) override;
468 bool getInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
470 bool setInteractionModeRaw(int j, yarp::dev::InteractionModeEnum _mode) override;
471 bool setInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
473
474 // IMotor interface
475 bool getNumberOfMotorsRaw(int * num) override;
476 bool getTemperatureRaw(int m, double* val) override;
477 bool getTemperaturesRaw(double *vals) override;
478 bool getTemperatureLimitRaw(int m, double *temp) override;
479 bool setTemperatureLimitRaw(int m, const double temp) override;
480
481 // PWM interface
482 bool setRefDutyCycleRaw(int j, double v) override;
483 bool setRefDutyCyclesRaw(const double *v) override;
484 bool getRefDutyCycleRaw(int j, double *v) override;
485 bool getRefDutyCyclesRaw(double *v) override;
486 bool getDutyCycleRaw(int j, double *v) override;
487 bool getDutyCyclesRaw(double *v) override;
488
489 // Current interface
490 //bool getAxes(int *ax) override;
491 //bool getCurrentRaw(int j, double *t) override;
492 //bool getCurrentsRaw(double *t) override;
493 bool getCurrentRangeRaw(int j, double *min, double *max) override;
494 bool getCurrentRangesRaw(double *min, double *max) override;
495 bool setRefCurrentsRaw(const double *t) override;
496 bool setRefCurrentRaw(int j, double t) override;
497 bool setRefCurrentsRaw(const int n_joint, const int *joints, const double *t) override;
498 bool getRefCurrentsRaw(double *t) override;
499 bool getRefCurrentRaw(int j, double *t) override;
500
504 bool updateVirtualAnalogSensorMeasureRaw(int ch, double &measure) override;
505
506 void run() override;
507private:
508 void cleanup();
509 bool dealloc();
510 bool parsePositionPidsGroup(yarp::os::Bottle& pidsGroup, yarp::dev::Pid myPid[]);
511 bool parseTorquePidsGroup(yarp::os::Bottle& pidsGroup, yarp::dev::Pid myPid[], double kbemf[], double ktau[], int filterType[], double viscousPos[], double viscousNeg[], double coulombPos[], double coulombNeg[]);
512
513 bool parseImpedanceGroup_NewFormat(yarp::os::Bottle& pidsGroup, ImpedanceParameters vals[]);
514
515 bool extractGroup(yarp::os::Bottle &input, yarp::os::Bottle &out, const std::string &key1, const std::string &txt, int size);
516};
517
518#endif // YARP_DEVICE_FAKE_MOTIONCONTROL
define control board standard interfaces
float t
virtual analog sensor interface
bool ret
contains the definition of a Vector type
fakeMotionControl: Documentation to be added
bool getPowerSupplyVoltageRaw(int j, double *val) override
bool getRefSpeedRaw(int j, double *ref) override
Get reference speed for a joint.
virtual bool getHasTempSensorsRaw(int j, int &ret)
bool setRefCurrentsRaw(const double *t) override
Set the reference value of the currents for all motors.
bool setRefTorqueRaw(int j, double t) override
Set the reference value of the torque for a given joint.
bool getCurrentsRaw(double *vals) override
bool getImpedanceOffsetRaw(int j, double *offset) override
Get current force Offset for a specific joint.
bool getTargetPositionRaw(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool getTorqueRangeRaw(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool getCurrentImpedanceLimitRaw(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 setTemperatureLimitRaw(int m, const double temp) override
Set the temperature limit for a specific motor.
bool getPidErrorRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
bool setPeakCurrentRaw(int m, const double val) override
bool velocityMoveRaw(int j, double sp) override
Start motion at a given speed, single joint.
bool checkMotionDoneRaw(bool *flag) override
Check if the current trajectory is terminated.
bool getMotorEncoderSpeedRaw(int m, double *sp) override
Read the istantaneous speed of a motor encoder.
virtual bool getJointEncoderTypeRaw(int j, int &type)
bool setRefDutyCycleRaw(int j, double v) override
Sets the reference dutycycle of a single motor.
bool getTemperatureRaw(int m, double *val) override
Get temperature of a motor.
bool getEncoderAccelerationRaw(int j, double *spds) override
Read the instantaneous acceleration of an axis.
bool getRefAccelerationRaw(int j, double *acc) override
Get reference acceleration for a joint.
bool getMotorEncoderSpeedsRaw(double *spds) override
Read the instantaneous speed of all motor encoders.
bool setPidsRaw(const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *pids) override
Set new pid value on multiple axes.
bool setVelLimitsRaw(int axis, double min, double max) override
Set the software speed limits for a particular axis, the behavior of the control card when these limi...
bool getJointTypeRaw(int axis, yarp::dev::JointTypeEnum &type) override
bool setMotorEncoderRaw(int m, const double val) override
Set the value of the motor encoder for a given motor.
bool getPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override
Get the error limit for the controller on a specific joint.
bool getPidOutputRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool setControlModeRaw(const int j, const int mode) override
bool getMotorEncoderAccelerationRaw(int m, double *spds) override
Read the instantaneous acceleration of a motor encoder.
bool open(yarp::os::Searchable &par) override
Open the DeviceDriver.
virtual bool getHasHallSensorRaw(int j, int &ret)
bool getTemperatureLimitRaw(int m, double *temp) override
Retreives the current temperature limit for a specific motor.
bool getNumberOfMotorsRaw(int *num) override
Retrieves the number of controlled motors from the current physical interface.
bool disableAmpRaw(int j) override
Disable the amplifier on a specific joint.
bool setMotorTorqueParamsRaw(int j, const yarp::dev::MotorTorqueParameters params) override
Set the motor parameters.
bool calibrateAxisWithParamsRaw(int axis, unsigned int type, double p1, double p2, double p3) override
Start calibration, this method is very often platform specific.
bool setRefAccelerationRaw(int j, double acc) override
Set reference acceleration for a joint.
virtual bool initialised()
bool setEncodersRaw(const double *vals) override
Set the value of all encoders.
bool getPidOutputsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool isPidEnabledRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid controller.
bool setRefSpeedsRaw(const double *spds) override
Set reference speed on all joints.
bool getTargetPositionsRaw(double *refs) override
Get the last position reference for all axes.
bool getRefDutyCycleRaw(int j, double *v) override
Gets the last reference sent using the setRefDutyCycleRaw function.
bool setMotorEncoderCountsPerRevolutionRaw(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
bool setPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
bool getPidReferenceRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override
Get the current reference of the pid controller for a specific joint.
bool getNominalCurrentRaw(int m, double *val) override
bool getControlModeRaw(int j, int *v) override
bool calibrationDoneRaw(int j) override
Check if the calibration is terminated, on a particular joint.
bool threadInit() override
Initialization method.
bool getRefDutyCyclesRaw(double *v) override
Gets the last reference sent using the setRefDutyCyclesRaw function.
bool getRefVelocityRaw(const int joint, double *ref) override
Get the last reference speed set by velocityMove for single joint.
bool getEncoderTimedRaw(int j, double *encs, double *stamp) override
Read the instantaneous acceleration of all axes.
bool disablePidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
yarp::dev::VAS_status getVirtualAnalogSensorStatusRaw(int ch) override
Check the status of a given channel.
bool getMotorEncodersRaw(double *encs) override
Read the position of all motor encoders.
bool getTorqueRangesRaw(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
bool getRefCurrentsRaw(double *t) override
Get the reference value of the currents for all motors.
bool setRefDutyCyclesRaw(const double *v) override
Sets the reference dutycycle for all motors.
bool getEncoderSpeedRaw(int j, double *sp) override
Read the instantaneous speed of an axis.
int getVirtualAnalogSensorChannelsRaw() override
Get the number of channels of the virtual sensor.
bool resetPidRaw(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 getCurrentRangesRaw(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool getEncoderRaw(int j, double *v) override
Read the value of an encoder.
bool getPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool enableAmpRaw(int j) override
Enable the amplifier on a specific joint.
bool fromConfig(yarp::os::Searchable &config)
bool getPidsRaw(const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
Get current pid value for a specific joint.
bool getRefPositionsRaw(double *refs) override
Get the last position reference for all axes.
bool getMotorTorqueParamsRaw(int j, yarp::dev::MotorTorqueParameters *params) override
Get the motor parameters.
bool setControlModesRaw(const int n_joint, const int *joints, int *modes) override
bool setRefSpeedRaw(int j, double sp) override
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
virtual bool getHasRotorEncoderIndexRaw(int j, int &ret)
bool updateVirtualAnalogSensorMeasureRaw(yarp::sig::Vector &measure) override
Set a vector of torque values for virtual sensor.
void resizeBuffers()
Resize previously allocated buffers.
void threadRelease() override
Release method.
bool getAmpStatusRaw(int *st) override
bool getLastJointFaultRaw(int j, int &fault, std::string &message) override
bool setImpedanceRaw(int j, double stiffness, double damping) override
Set current impedance parameters (stiffness,damping) for a specific joint.
bool setPWMLimitRaw(int j, const double val) override
bool relativeMoveRaw(int j, double delta) override
Set relative position.
virtual bool getMotorPolesRaw(int j, int &poles)
bool getPidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *pid) override
Get current pid value for a specific joint.
bool getCurrentRaw(int j, double *val) override
bool getPeakCurrentRaw(int m, double *val) override
bool getDutyCyclesRaw(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool setEncoderRaw(int j, double val) override
Set the value of the encoder for a given joint.
bool getRefPositionRaw(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool getLimitsRaw(int axis, double *min, double *max) override
Get the software limits for a particular axis.
virtual bool getRotorIndexOffsetRaw(int j, double &rotorOffset)
bool getVelLimitsRaw(int axis, double *min, double *max) override
Get the software speed limits for a particular axis.
bool setPositionsRaw(const int n_joint, const int *joints, const double *refs) override
Set new reference point for all axes.
bool setPidReferenceRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool resetEncodersRaw() override
Reset encoders.
bool getPWMRaw(int j, double *val) override
bool getAxisNameRaw(int axis, std::string &name) override
bool setCalibrationParametersRaw(int axis, const yarp::dev::CalibrationParameters &params) override
Start calibration, this method is very often platform specific.
bool setPidOffsetRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
Set an offset value on the ourput of pid controller.
bool getInteractionModeRaw(int j, yarp::dev::InteractionModeEnum *_mode) override
Get the current interaction mode of the robot, values can be stiff or compliant.
bool getCurrentRangeRaw(int j, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool stopRaw() override
Stop motion, multiple joints.
virtual bool getKinematicMJRaw(int j, double &rotres)
bool getRefSpeedsRaw(double *spds) override
Get reference speed of all joints.
bool getRefAccelerationsRaw(double *accs) override
Get reference acceleration of all joints.
virtual bool getJointEncoderResolutionRaw(int m, double &jntres)
bool getAxes(int *ax) override
Get the number of controlled axes.
bool setMaxCurrentRaw(int j, double val) override
bool alloc(int njoints)
Allocated buffers.
bool resetMotorEncodersRaw() override
Reset motor encoders.
bool setRefTorquesRaw(const double *t) override
Set the reference value of the torque for all joints.
bool getEncodersRaw(double *encs) override
Read the position of all axes.
bool setRefAccelerationsRaw(const double *accs) override
Set reference acceleration on all joints.
bool getControlModesRaw(int *v) override
bool setPidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &pid) override
Set new pid value for a joint axis.
bool getPWMLimitRaw(int j, double *val) override
virtual bool getRotorEncoderTypeRaw(int j, int &type)
bool getRefCurrentRaw(int j, double *t) override
Get the reference value of the current for a single motor.
bool getDutyCycleRaw(int j, double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool setPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
Set the error limit for the controller on a specific joint.
bool getInteractionModesRaw(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 positionMoveRaw(int j, double ref) override
Set new reference point for a single axis.
bool getMotorEncoderCountsPerRevolutionRaw(int m, double *v) override
Gets number of counts per revolution for motor encoder m.
bool setImpedanceOffsetRaw(int j, double offset) override
Set current force Offset for a specific joint.
bool setMotorEncodersRaw(const double *vals) override
Set the value of all motor encoders.
bool getPidErrorsRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool getGearboxRatioRaw(int m, double *gearbox) override
Get the gearbox ratio for a specific motor.
bool getMaxCurrentRaw(int j, double *val) override
Returns the maximum electric current allowed for a given motor.
bool close() override
Close the DeviceDriver.
bool getRefTorquesRaw(double *t) override
Get the reference value of the torque for all joints.
bool setRefCurrentRaw(int j, double t) override
Set the reference value of the current for a single motor.
bool getNumberOfMotorEncodersRaw(int *num) override
Get the number of available motor encoders.
bool getPidReferencesRaw(const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool getTorqueRaw(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 getImpedanceRaw(int j, double *stiffness, double *damping) override
Get current impedance parameters (stiffness,damping,offset) for a specific joint.
bool enablePidRaw(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Enable the pid computation for a joint.
bool getRefVelocitiesRaw(double *refs) override
Get the last reference speed set by velocityMove for all joints.
bool setPositionRaw(int j, double ref) override
Set new position for a single axis.
bool getEncoderAccelerationsRaw(double *accs) override
Read the instantaneous acceleration of all axes.
bool setPidReferencesRaw(const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
bool getMotorEncoderRaw(int m, double *v) override
Read the value of a motor encoder.
bool getRefTorqueRaw(int j, double *t) override
Set the reference value of the torque for a given joint.
bool getMotorEncoderAccelerationsRaw(double *accs) override
Read the instantaneous acceleration of all motor encoders.
bool setInteractionModesRaw(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 getTemperaturesRaw(double *vals) override
Get temperature of all the motors.
bool resetMotorEncoderRaw(int m) override
Reset motor encoder, single motor.
bool setNominalCurrentRaw(int m, const double val) override
virtual bool getRotorEncoderResolutionRaw(int m, double &rotres)
virtual bool getHasRotorEncoderRaw(int j, int &ret)
bool getMotorEncodersTimedRaw(double *encs, double *stamps) override
Read the instantaneous position of all motor encoders.
bool resetEncoderRaw(int j) override
Reset encoder, single joint.
bool getTorquesRaw(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool setLimitsRaw(int axis, double min, double max) override
Set the software limits for a particular axis, the behavior of the control card when these limits are...
bool setInteractionModeRaw(int j, yarp::dev::InteractionModeEnum _mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
void run() override
Loop function.
bool getMotorEncoderTimedRaw(int m, double *encs, double *stamp) override
Read the instantaneous position of a motor encoder.
bool getEncodersTimedRaw(double *encs, double *stamps) override
Read the instantaneous acceleration of all axes.
bool getEncoderSpeedsRaw(double *spds) override
Read the instantaneous acceleration of an axis.
virtual bool getTorqueControlFilterType(int j, int &type)
Interface implemented by all device drivers.
Definition: DeviceDriver.h:30
Interface for control devices, amplifier commands.
Interface for getting information about specific axes, if available.
Definition: IAxisInfo.h:62
Interface for control devices, calibration commands.
Interface for control devices.
Interface for setting control mode in control board.
Definition: IControlMode.h:99
Interface for control boards implementing current control.
Control board, extend encoder raw interface adding 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:35
Control board, encoder interface.
Control board, encoder interface.
Definition: IMotor.h:24
Interface for controlling an axis, by sending directly a PWM reference signal to a motor.
Definition: IPWMControl.h:83
Interface for a generic control board device implementing a PID controller.
Definition: IPidControl.h:25
Interface for a generic control board device implementing position control in encoder coordinates.
Interface for a generic control board device implementing position control in encoder coordinates.
Interface for control boards implementing torque control.
Interface for control boards implementig velocity control in encoder coordinates.
A generic interface to a virtual sensors.
class ImplementControlLimits; class StubImplControlLimitsRaw;
Interface settings the way the robot interacts with the environment: basic interaction types are Stif...
Default implementation of the IPositionControl interface.
Default implementation of the IPositionDirect interface.
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
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:63
PidControlTypeEnum
Definition: PidEnums.h:15
ImpedanceLimits limits