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>
12 #include <yarp/os/PeriodicThread.h>
13 #include <yarp/dev/DeviceDriver.h>
20 
21 #include <mutex>
22 
23 
25 {
26  double min_stiff;
27  double max_stiff;
28  double min_damp;
29  double max_damp;
30  double param_a;
31  double param_b;
32  double param_c;
33 
34 public:
36  {
37  min_stiff=0;
38  max_stiff=0;
39  min_damp=0;
40  max_damp=0;
41  param_a=0;
42  param_b=0;
43  param_c=0;
44  }
45 
46  double get_min_stiff()
47  {
48  return min_stiff;
49  }
50  double get_max_stiff()
51  {
52  return max_stiff;
53  }
54  double get_min_damp()
55  {
56  return min_damp;
57  }
58  double get_max_damp()
59  {
60  return max_damp;
61  }
62 };
63 
65 {
66  double stiffness;
67  double damping;
70 };
71 
87 // public yarp::dev::DeviceResponder,
94  public yarp::dev::IMotorRaw,
125 {
126 private:
127  enum VerboseLevel
128  {
129  MUTE = 0, // only errors that prevent device from working
130  QUIET = 1, // adds errors that can cause malfunctioning
131  DEFAULT = 2, // adds warnings // DEFAULT // show noisy messages about back-compatible changes
132  CHATTY = 3, // adds info messages
133  VERBOSE = 4, // adds debug messages
134  VERY_VERBOSE = 5, // adds trace of events (shows thread running and catch if they get stuck)
135  VERY_VERY_VERBOSE = 6 // adds messages printed every cycle, so too much verbose for usage, only for deep debugging
136  };
137 
138  std::mutex _mutex;
139  int _njoints;
140  int *_axisMap;
141  double *_angleToEncoder;
142  double *_encodersStamp;
143  double *_ampsToSensor;
144  double *_dutycycleToPWM;
145  float *_DEPRECATED_encoderconversionfactor;
146  float *_DEPRECATED_encoderconversionoffset;
147 // uint8_t *_jointEncoderType; /** joint encoder type*/
148  int *_jointEncoderRes;
149  int *_rotorEncoderRes;
150 // uint8_t *_rotorEncoderType; /** rotor encoder type*/
151  double *_gearbox;
152  bool *_hasHallSensor;
153  bool *_hasTempSensor;
154  bool *_hasRotorEncoder;
155  bool *_hasRotorEncoderIndex;
156  int *_rotorIndexOffset;
157  int *_motorPoles;
158  double *_rotorlimits_max;
159  double *_rotorlimits_min;
160  yarp::dev::Pid *_ppids;
161  yarp::dev::Pid *_tpids;
162  yarp::dev::Pid *_cpids;
163  yarp::dev::Pid *_vpids;
164  bool *_ppids_ena;
165  bool *_tpids_ena;
166  bool *_cpids_ena;
167  bool *_vpids_ena;
168  double *_ppids_lim;
169  double *_tpids_lim;
170  double *_cpids_lim;
171  double *_vpids_lim;
172  double *_ppids_ref;
173  double *_tpids_ref;
174  double *_cpids_ref;
175  double *_vpids_ref;
176 
177  std::string *_axisName;
178  yarp::dev::JointTypeEnum *_jointType;
179 // ImpedanceLimits *_impedance_limits; /** impedance limits */
180  double *_limitsMin;
181  double *_limitsMax;
182  double *_kinematic_mj;
183  //double *_currentLimits; /** current limits */
184 // MotorCurrentLimits *_currentLimits;
185  double *_maxJntCmdVelocity;
186  double *_maxMotorVelocity;
187  int *_velocityShifts;
188  int *_velocityTimeout;
189  double *_kbemf;
190  double *_ktau;
191  int *_kbemf_scale;
192  int *_ktau_scale;
193  int * _filterType;
194  int *_torqueSensorId;
195  int *_torqueSensorChan;
196  double *_maxTorque;
197  double *_newtonsToSensor;
198  bool *checking_motiondone; /* flag telling if I'm already waiting for motion done */
199  double *_last_position_move_time;
200  double *_motorPwmLimits;
201  double *_torques;
203 // ImpedanceParameters *_impedance_params; /** impedance parameters */
204 
205  bool verbosewhenok;
206  bool useRawEncoderData;
207  bool _pwmIsLimited;
208  bool _torqueControlEnabled;
210  enum torqueControlUnitsType {T_MACHINE_UNITS=0, T_METRIC_UNITS=1};
211  torqueControlUnitsType _torqueControlUnits;
212 
213  enum positionControlUnitsType {P_MACHINE_UNITS=0, P_METRIC_UNITS=1};
214  positionControlUnitsType _positionControlUnits;
215 
216  // internal stuff
217  int *_controlModes;
218  int *_interactMode;
219  bool *_enabledAmp; // 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.
220  bool *_enabledPid; // 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.
221  bool *_calibrated; // Flag to know if the calibrate function has been called for the joint
222  double *_posCtrl_references; // used for position control.
223  double *_posDir_references; // used for position Direct control.
224  double *_ref_speeds; // used for position control.
225  double *_command_speeds; // used for velocity control.
226  double *_ref_accs; // for velocity control, in position min jerk eq is used.
227  double *_ref_torques; // for torque control.
228  double *_ref_currents;
229  yarp::sig::Vector current, nominalCurrent, maxCurrent, peakCurrent;
230  yarp::sig::Vector pwm, pwmLimit, refpwm, supplyVoltage,last_velocity_command, last_pwm_command;
231  yarp::sig::Vector pos, dpos, vel, speed, acc, loc, amp;
232  double prev_time;
233  bool opened;
234 
235  // debugging
236  VerboseLevel verbose;
237 public:
238 
241 
242  // Device Driver
243  bool open(yarp::os::Searchable &par) override;
244  bool close() override;
245  bool fromConfig(yarp::os::Searchable &config);
246 
247  virtual bool initialised();
248 
252  bool alloc(int njoints);
253 
257  void resizeBuffers();
258 
259  bool threadInit() override;
260  void threadRelease() override;
261 
263  bool setPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, const yarp::dev::Pid &pid) override;
264  bool setPidsRaw(const yarp::dev::PidControlTypeEnum& pidtype,const yarp::dev::Pid *pids) override;
265  bool setPidReferenceRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double ref) override;
266  bool setPidReferencesRaw(const yarp::dev::PidControlTypeEnum& pidtype,const double *refs) override;
267  bool setPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double limit) override;
268  bool setPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum& pidtype,const double *limits) override;
269  bool getPidErrorRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *err) override;
270  bool getPidErrorsRaw(const yarp::dev::PidControlTypeEnum& pidtype, double *errs) override;
271  bool getPidOutputRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *out) override;
272  bool getPidOutputsRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *outs) override;
273  bool getPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, yarp::dev::Pid *pid) override;
274  bool getPidsRaw(const yarp::dev::PidControlTypeEnum& pidtype, yarp::dev::Pid *pids) override;
275  bool getPidReferenceRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *ref) override;
276  bool getPidReferencesRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *refs) override;
277  bool getPidErrorLimitRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double *limit) override;
278  bool getPidErrorLimitsRaw(const yarp::dev::PidControlTypeEnum& pidtype,double *limits) override;
279  bool resetPidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
280  bool disablePidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
281  bool enablePidRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j) override;
282  bool setPidOffsetRaw(const yarp::dev::PidControlTypeEnum& pidtype,int j, double v) override;
283  bool isPidEnabledRaw(const yarp::dev::PidControlTypeEnum& pidtype, int j, bool* enabled) override;
284 
285  // POSITION CONTROL INTERFACE RAW
286  bool getAxes(int *ax) override;
287  bool positionMoveRaw(int j, double ref) override;
288  bool positionMoveRaw(const double *refs) override;
289  bool relativeMoveRaw(int j, double delta) override;
290  bool relativeMoveRaw(const double *deltas) override;
291  bool checkMotionDoneRaw(bool *flag) override;
292  bool checkMotionDoneRaw(int j, bool *flag) override;
293  bool setRefSpeedRaw(int j, double sp) override;
294  bool setRefSpeedsRaw(const double *spds) override;
295  bool setRefAccelerationRaw(int j, double acc) override;
296  bool setRefAccelerationsRaw(const double *accs) override;
297  bool getRefSpeedRaw(int j, double *ref) override;
298  bool getRefSpeedsRaw(double *spds) override;
299  bool getRefAccelerationRaw(int j, double *acc) override;
300  bool getRefAccelerationsRaw(double *accs) override;
301  bool stopRaw(int j) override;
302  bool stopRaw() override;
303 
304  // Position Control2 Interface
305  bool positionMoveRaw(const int n_joint, const int *joints, const double *refs) override;
306  bool relativeMoveRaw(const int n_joint, const int *joints, const double *deltas) override;
307  bool checkMotionDoneRaw(const int n_joint, const int *joints, bool *flags) override;
308  bool setRefSpeedsRaw(const int n_joint, const int *joints, const double *spds) override;
309  bool setRefAccelerationsRaw(const int n_joint, const int *joints, const double *accs) override;
310  bool getRefSpeedsRaw(const int n_joint, const int *joints, double *spds) override;
311  bool getRefAccelerationsRaw(const int n_joint, const int *joints, double *accs) override;
312  bool stopRaw(const int n_joint, const int *joints) override;
313  bool getTargetPositionRaw(const int joint, double *ref) override;
314  bool getTargetPositionsRaw(double *refs) override;
315  bool getTargetPositionsRaw(const int n_joint, const int *joints, double *refs) override;
316 
317  // Velocity control interface raw
318  bool velocityMoveRaw(int j, double sp) override;
319  bool velocityMoveRaw(const double *sp) override;
320 
321 
322  // calibration2raw
323  bool setCalibrationParametersRaw(int axis, const yarp::dev::CalibrationParameters& params) override;
324  bool calibrateAxisWithParamsRaw(int axis, unsigned int type, double p1, double p2, double p3) override;
325  bool calibrationDoneRaw(int j) override;
326 
327 
329 
330  // ControlMode
331  bool getControlModeRaw(int j, int *v) override;
332  bool getControlModesRaw(int *v) override;
333 
334  // ControlMode 2
335  bool getControlModesRaw(const int n_joint, const int *joints, int *modes) override;
336  bool setControlModeRaw(const int j, const int mode) override;
337  bool setControlModesRaw(const int n_joint, const int *joints, int *modes) override;
338  bool setControlModesRaw(int *modes) override;
339 
341  bool resetEncoderRaw(int j) override;
342  bool resetEncodersRaw() override;
343  bool setEncoderRaw(int j, double val) override;
344  bool setEncodersRaw(const double *vals) override;
345  bool getEncoderRaw(int j, double *v) override;
346  bool getEncodersRaw(double *encs) override;
347  bool getEncoderSpeedRaw(int j, double *sp) override;
348  bool getEncoderSpeedsRaw(double *spds) override;
349  bool getEncoderAccelerationRaw(int j, double *spds) override;
350  bool getEncoderAccelerationsRaw(double *accs) override;
352 
353  bool getEncodersTimedRaw(double *encs, double *stamps) override;
354  bool getEncoderTimedRaw(int j, double *encs, double *stamp) override;
355 
357  bool getNumberOfMotorEncodersRaw(int * num) override;
358  bool resetMotorEncoderRaw(int m) override;
359  bool resetMotorEncodersRaw() override;
360  bool setMotorEncoderRaw(int m, const double val) override;
361  bool setMotorEncodersRaw(const double *vals) override;
362  bool getMotorEncoderRaw(int m, double *v) override;
363  bool getMotorEncodersRaw(double *encs) override;
364  bool getMotorEncoderSpeedRaw(int m, double *sp) override;
365  bool getMotorEncoderSpeedsRaw(double *spds) override;
366  bool getMotorEncoderAccelerationRaw(int m, double *spds) override;
367  bool getMotorEncoderAccelerationsRaw(double *accs) override;
368  bool getMotorEncodersTimedRaw(double *encs, double *stamps) override;
369  bool getMotorEncoderTimedRaw(int m, double *encs, double *stamp) override;\
370  bool getMotorEncoderCountsPerRevolutionRaw(int m, double *v) override;
371  bool setMotorEncoderCountsPerRevolutionRaw(int m, const double cpr) override;
373 
375  bool getAxisNameRaw(int axis, std::string& name) override;
376  bool getJointTypeRaw(int axis, yarp::dev::JointTypeEnum& type) override;
378 
379  //Internal use, not exposed by YARP (yet)
380  bool getGearboxRatioRaw(int m, double *gearbox) override;
381  virtual bool getRotorEncoderResolutionRaw(int m, double &rotres);
382  virtual bool getJointEncoderResolutionRaw(int m, double &jntres);
383  virtual bool getJointEncoderTypeRaw(int j, int &type);
384  virtual bool getRotorEncoderTypeRaw(int j, int &type);
385  virtual bool getKinematicMJRaw(int j, double &rotres);
386  virtual bool getHasTempSensorsRaw(int j, int& ret);
387  virtual bool getHasHallSensorRaw(int j, int& ret);
388  virtual bool getHasRotorEncoderRaw(int j, int& ret);
389  virtual bool getHasRotorEncoderIndexRaw(int j, int& ret);
390  virtual bool getMotorPolesRaw(int j, int& poles);
391  virtual bool getRotorIndexOffsetRaw(int j, double& rotorOffset);
392  virtual bool getTorqueControlFilterType(int j, int& type);
393 
395  bool enableAmpRaw(int j) override;
396  bool disableAmpRaw(int j) override;
397  bool getCurrentsRaw(double *vals) override;
398  bool getCurrentRaw(int j, double *val) override;
399  bool getNominalCurrentRaw(int m, double *val) override;
400  bool setNominalCurrentRaw(int m, const double val) override;
401  bool setMaxCurrentRaw(int j, double val) override;
402  bool getMaxCurrentRaw(int j, double *val) override;
403  bool getPeakCurrentRaw(int m, double *val) override;
404  bool setPeakCurrentRaw(int m, const double val) override;
405  bool getAmpStatusRaw(int *st) override;
406  bool getAmpStatusRaw(int j, int *st) override;
407  bool getPWMRaw(int j, double* val) override;
408  bool getPWMLimitRaw(int j, double* val) override;
409  bool setPWMLimitRaw(int j, const double val) override;
410  bool getPowerSupplyVoltageRaw(int j, double* val) override;
412 
413  // Limits
414  bool setLimitsRaw(int axis, double min, double max) override;
415  bool getLimitsRaw(int axis, double *min, double *max) override;
416  // Limits 2
417  bool setVelLimitsRaw(int axis, double min, double max) override;
418  bool getVelLimitsRaw(int axis, double *min, double *max) override;
419 
420  // Torque control
421  bool getTorqueRaw(int j, double *t) override;
422  bool getTorquesRaw(double *t) override;
423  bool getTorqueRangeRaw(int j, double *min, double *max) override;
424  bool getTorqueRangesRaw(double *min, double *max) override;
425  bool setRefTorquesRaw(const double *t) override;
426  bool setRefTorqueRaw(int j, double t) override;
427  bool setRefTorquesRaw(const int n_joint, const int *joints, const double *t) override;
428  bool getRefTorquesRaw(double *t) override;
429  bool getRefTorqueRaw(int j, double *t) override;
430  bool getMotorTorqueParamsRaw(int j, yarp::dev::MotorTorqueParameters *params) override;
431  bool setMotorTorqueParamsRaw(int j, const yarp::dev::MotorTorqueParameters params) override;
432 // int32_t getRefSpeedInTbl(uint8_t boardNum, int j, eOmeas_position_t pos) override;
433 
434  // IVelocityControl interface
435  bool velocityMoveRaw(const int n_joint, const int *joints, const double *spds) override;
436  bool getRefVelocityRaw(const int joint, double *ref) override;
437  bool getRefVelocitiesRaw(double *refs) override;
438  bool getRefVelocitiesRaw(const int n_joint, const int *joints, double *refs) override;
439 
440  // Impedance interface
441  bool getImpedanceRaw(int j, double *stiffness, double *damping) override;
442  bool setImpedanceRaw(int j, double stiffness, double damping) override;
443  bool setImpedanceOffsetRaw(int j, double offset) override;
444  bool getImpedanceOffsetRaw(int j, double *offset) override;
445  bool getCurrentImpedanceLimitRaw(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
446 
447  // PositionDirect Interface
448  bool setPositionRaw(int j, double ref) override;
449  bool setPositionsRaw(const int n_joint, const int *joints, const double *refs) override;
450  bool setPositionsRaw(const double *refs) override;
451  bool getRefPositionRaw(const int joint, double *ref) override;
452  bool getRefPositionsRaw(double *refs) override;
453  bool getRefPositionsRaw(const int n_joint, const int *joints, double *refs) override;
454 
455  // InteractionMode interface
456  bool getInteractionModeRaw(int j, yarp::dev::InteractionModeEnum* _mode) override;
457  bool getInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
459  bool setInteractionModeRaw(int j, yarp::dev::InteractionModeEnum _mode) override;
460  bool setInteractionModesRaw(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
462 
463  // IMotor interface
464  bool getNumberOfMotorsRaw(int * num) override;
465  bool getTemperatureRaw(int m, double* val) override;
466  bool getTemperaturesRaw(double *vals) override;
467  bool getTemperatureLimitRaw(int m, double *temp) override;
468  bool setTemperatureLimitRaw(int m, const double temp) override;
469 
470  // PWM interface
471  bool setRefDutyCycleRaw(int j, double v) override;
472  bool setRefDutyCyclesRaw(const double *v) override;
473  bool getRefDutyCycleRaw(int j, double *v) override;
474  bool getRefDutyCyclesRaw(double *v) override;
475  bool getDutyCycleRaw(int j, double *v) override;
476  bool getDutyCyclesRaw(double *v) override;
477 
478  // Current interface
479  //bool getAxes(int *ax) override;
480  //bool getCurrentRaw(int j, double *t) override;
481  //bool getCurrentsRaw(double *t) override;
482  bool getCurrentRangeRaw(int j, double *min, double *max) override;
483  bool getCurrentRangesRaw(double *min, double *max) override;
484  bool setRefCurrentsRaw(const double *t) override;
485  bool setRefCurrentRaw(int j, double t) override;
486  bool setRefCurrentsRaw(const int n_joint, const int *joints, const double *t) override;
487  bool getRefCurrentsRaw(double *t) override;
488  bool getRefCurrentRaw(int j, double *t) override;
489 
491  int getVirtualAnalogSensorChannelsRaw() override;
493  bool updateVirtualAnalogSensorMeasureRaw(int ch, double &measure) override;
494 
495  void run() override;
496 private:
497  void cleanup();
498  bool dealloc();
499  bool parsePositionPidsGroup(yarp::os::Bottle& pidsGroup, yarp::dev::Pid myPid[]);
500  bool parseTorquePidsGroup(yarp::os::Bottle& pidsGroup, yarp::dev::Pid myPid[], double kbemf[], double ktau[], int filterType[]);
501  bool parseImpedanceGroup_NewFormat(yarp::os::Bottle& pidsGroup, ImpedanceParameters vals[]);
502 
503  bool extractGroup(yarp::os::Bottle &input, yarp::os::Bottle &out, const std::string &key1, const std::string &txt, int size);
504 };
505 
506 #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 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:35
Interface for control devices, amplifier commands.
Interface for getting information about specific axes, if available.
Definition: IAxisInfo.h:66
Interface for control devices, calibration commands.
Interface for control devices.
Interface for setting control mode in control board.
Definition: IControlMode.h:101
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...
Control board, encoder interface.
Control board, encoder interface.
Definition: IMotor.h:26
Interface for controlling an axis, by sending directly a PWM reference signal to a motor.
Definition: IPWMControl.h:85
Interface for a generic control board device implementing a PID controller.
Definition: IPidControl.h:29
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:74
An abstraction for a periodic thread.
A base class for nested structures that can be searched.
Definition: Searchable.h:66
PidControlTypeEnum
Definition: PidEnums.h:18
ImpedanceLimits limits