YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
RemoteControlBoard.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4 * SPDX-License-Identifier: BSD-3-Clause
5 */
6
7#ifndef YARP_DEV_REMOTECONTROLBOARD_REMOTECONTROLBOARD_H
8#define YARP_DEV_REMOTECONTROLBOARD_REMOTECONTROLBOARD_H
9
10#include <yarp/sig/Vector.h>
11
17#include <yarp/dev/IMotor.h>
20#include <yarp/dev/IAxisInfo.h>
35
36#include "stateExtendedReader.h"
37
39{
40 int major{0};
41 int minor{0};
42 int tweak{0};
43};
44
46
47
72 public yarp::dev::IMotor,
89{
90protected:
94
99
100 // Buffer associated to the extendedOutputStatePort port; in this case we will use the type generated
101 // from the YARP .thrift file
102// yarp::os::PortReaderBuffer<jointData> extendedInputState_buffer; // Buffer storing new data
103 StateExtendedInputPort extendedIntputStatePort; // Buffered port storing new data
105 yarp::dev::impl::jointData last_singleJoint; // tmp to store last received data for a particular joint
106// yarp::os::Port extendedIntputStatePort; // Port /stateExt:i reading the state of the joints
107 yarp::dev::impl::jointData last_wholePart; // tmp to store last received data for whole part
108
109 std::string remote;
110 std::string local;
111 mutable Stamp lastStamp; //this is shared among all calls that read encoders
112 size_t nj{0};
113 bool njIsKnown{false};
114
116
117 // Check for number of joints, if needed.
118 // This is to allow for delayed connection to the remote control board.
119 bool isLive();
120
121 bool checkProtocolVersion(bool ignore);
122
123 bool send1V(int v);
124 bool send2V(int v1, int v2);
125 bool send2V1I(int v1, int v2, int axis);
126 bool send1V1I(int v, int axis);
127 bool send3V1I(int v1, int v2, int v3, int j);
128
134 bool set1V(int code);
135
143 bool set1V2D(int code, double v);
144
152 bool set1V1I(int code, int v);
153
160 bool get1V1D(int code, double& v) const;
161
168 bool get1V1I(int code, int& v) const;
169
177 bool set1V1I1D(int code, int j, double val);
178
179 bool set1V1I2D(int code, int j, double val1, double val2);
180
187 bool set1VDA(int v, const double *val);
188 bool set2V1DA(int v1, int v2, const double *val);
189 bool set2V2DA(int v1, int v2, const double *val1, const double *val2);
190 bool set1V1I1IA1DA(int v, const int len, const int *val1, const double *val2);
191 bool set2V1I1D(int v1, int v2, int axis, double val);
192 bool setValWithPidType(int voc, PidControlTypeEnum type, int axis, double val);
193 bool setValWithPidType(int voc, PidControlTypeEnum type, const double* val_arr);
194 bool getValWithPidType(int voc, PidControlTypeEnum type, int j, double *val);
195 bool getValWithPidType(int voc, PidControlTypeEnum type, double *val);
196 bool set2V1I(int v1, int v2, int axis);
197
205 bool get1V1I1D(int v, int j, double *val);
206
214 bool get1V1I1I(int v, int j, int *val);
215 bool get2V1I1D(int v1, int v2, int j, double *val);
216 bool get2V1I2D(int v1, int v2, int j, double *val1, double *val2);
217 bool get1V1I2D(int code, int axis, double *v1, double *v2);
218
226 bool get1V1I1B(int v, int j, bool &val);
227 bool get1V1I1IA1B(int v, const int len, const int *val1, bool &retVal);
228 bool get2V1I1IA1DA(int v1, int v2, const int n_joints, const int *joints, double *retVals, std::string functionName = "");
229 bool get1V1B(int v, bool &val);
230
237 bool get1VIA(int v, int *val);
238
245 bool get1VDA(int v, double *val);
246
253 bool get1V1DA(int v1, double *val);
254
262 bool get2V1DA(int v1, int v2, double *val);
263
264 bool get2V2DA(int v1, int v2, double *val1, double *val2);
265
266 bool get1V1I1S(int code, int j, std::string &name);
267
268 bool get1V1I1IA1DA(int v, const int len, const int *val1, double *val2);
269
270public:
276 ~RemoteControlBoard() override = default;
277
278 bool open(Searchable& config) override;
279
284 bool close() override;
285
286 bool getAxes(int *ax) override;
287
288 // IPidControl
289 bool setPid(const PidControlTypeEnum& pidtype, int j, const Pid &pid) override;
290 bool setPids(const PidControlTypeEnum& pidtype, const Pid *pids) override;
291 bool setPidReference(const PidControlTypeEnum& pidtype, int j, double ref) override;
292 bool setPidReferences(const PidControlTypeEnum& pidtype, const double *refs) override;
293 bool setPidErrorLimit(const PidControlTypeEnum& pidtype, int j, double limit) override;
294 bool setPidErrorLimits(const PidControlTypeEnum& pidtype, const double *limits) override;
295 bool getPidError(const PidControlTypeEnum& pidtype, int j, double *err) override;
296 bool getPidErrors(const PidControlTypeEnum& pidtype, double *errs) override;
297 bool getPid(const PidControlTypeEnum& pidtype, int j, Pid *pid) override;
298 bool getPids(const PidControlTypeEnum& pidtype, Pid *pids) override;
299 bool getPidReference(const PidControlTypeEnum& pidtype, int j, double *ref) override;
300 bool getPidReferences(const PidControlTypeEnum& pidtype, double *refs) override;
301 bool getPidErrorLimit(const PidControlTypeEnum& pidtype, int j, double *limit) override;
302 bool getPidErrorLimits(const PidControlTypeEnum& pidtype, double *limits) override;
303 bool resetPid(const PidControlTypeEnum& pidtype, int j) override;
304 bool disablePid(const PidControlTypeEnum& pidtype, int j) override;
305 bool enablePid(const PidControlTypeEnum& pidtype, int j) override;
306 bool isPidEnabled(const PidControlTypeEnum& pidtype, int j, bool* enabled) override;
307 bool getPidOutput(const PidControlTypeEnum& pidtype, int j, double *out) override;
308 bool getPidOutputs(const PidControlTypeEnum& pidtype, double *outs) override;
309 bool setPidOffset(const PidControlTypeEnum& pidtype, int j, double v) override;
310
311 // IEncoder
312 bool resetEncoder(int j) override;
313 bool resetEncoders() override;
314 bool setEncoder(int j, double val) override;
315 bool setEncoders(const double *vals) override;
316 bool getEncoder(int j, double *v) override;
317 bool getEncoderTimed(int j, double *v, double *t) override;
318 bool getEncoders(double *encs) override;
319 bool getEncodersTimed(double *encs, double *ts) override;
320 bool getEncoderSpeed(int j, double *sp) override;
321 bool getEncoderSpeeds(double *spds) override;
322 bool getEncoderAcceleration(int j, double *acc) override;
323 bool getEncoderAccelerations(double *accs) override;
324
325 // IRemoteVariable
326 bool getRemoteVariable(std::string key, yarp::os::Bottle& val) override;
327 bool setRemoteVariable(std::string key, const yarp::os::Bottle& val) override;
329
330 // IMotor
331 bool getNumberOfMotors(int *num) override;
332 bool getTemperature(int m, double* val) override;
333 bool getTemperatures(double *vals) override;
334 bool getTemperatureLimit (int m, double* val) override;
335 bool setTemperatureLimit (int m, const double val) override;
336 bool getGearboxRatio(int m, double* val) override;
337 bool setGearboxRatio(int m, const double val) override;
338
339 // IMotorEncoder
340 bool resetMotorEncoder(int j) override;
341 bool resetMotorEncoders() override;
342 bool setMotorEncoder(int j, const double val) override;
343 bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override;
344 bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override;
345 bool setMotorEncoders(const double *vals) override;
346 bool getMotorEncoder(int j, double *v) override;
347 bool getMotorEncoderTimed(int j, double *v, double *t) override;
348 bool getMotorEncoders(double *encs) override;
349 bool getMotorEncodersTimed(double *encs, double *ts) override;
350 bool getMotorEncoderSpeed(int j, double *sp) override;
351 bool getMotorEncoderSpeeds(double *spds) override;
352 bool getMotorEncoderAcceleration(int j, double *acc) override;
353 bool getMotorEncoderAccelerations(double *accs) override;
354 bool getNumberOfMotorEncoders(int *num) override;
355
356 // IPreciselyTimed
357 Stamp getLastInputStamp() override;
358
359 // IPositionControl
360 bool positionMove(int j, double ref) override;
361 bool positionMove(const int n_joint, const int *joints, const double *refs) override;
362 bool positionMove(const double *refs) override;
363 bool getTargetPosition(const int joint, double *ref) override;
364 bool getTargetPositions(double *refs) override;
365 bool getTargetPositions(const int n_joint, const int *joints, double *refs) override;
366 bool relativeMove(int j, double delta) override;
367 bool relativeMove(const int n_joint, const int *joints, const double *refs) override;
368 bool relativeMove(const double *deltas) override;
369 bool checkMotionDone(int j, bool *flag) override;
370 bool checkMotionDone(const int n_joint, const int *joints, bool *flag) override;
371 bool checkMotionDone(bool *flag) override;
372 bool setRefSpeed(int j, double sp) override;
373 bool setRefSpeeds(const int n_joint, const int *joints, const double *spds) override;
374 bool setRefSpeeds(const double *spds) override;
375 bool setRefAcceleration(int j, double acc) override;
376 bool setRefAccelerations(const int n_joint, const int *joints, const double *accs) override;
377 bool setRefAccelerations(const double *accs) override;
378 bool getRefSpeed(int j, double *ref) override;
379 bool getRefSpeeds(const int n_joint, const int *joints, double *spds) override;
380 bool getRefSpeeds(double *spds) override;
381 bool getRefAcceleration(int j, double *acc) override;
382 bool getRefAccelerations(const int n_joint, const int *joints, double *accs) override;
383 bool getRefAccelerations(double *accs) override;
384 bool stop(int j) override;
385 bool stop(const int len, const int *val1) override;
386 bool stop() override;
387
388 // IJointFault
389 bool getLastJointFault(int j, int& fault, std::string& message) override;
390
391 // IVelocityControl
392 bool velocityMove(int j, double v) override;
393 bool velocityMove(const double *v) override;
394
395 // IAmplifierControl
396 bool enableAmp(int j) override;
397 bool disableAmp(int j) override;
398 bool getAmpStatus(int *st) override;
399 bool getAmpStatus(int j, int *st) override;
400 bool setMaxCurrent(int j, double v) override;
401 bool getMaxCurrent(int j, double *v) override;
402 bool getNominalCurrent(int m, double *val) override;
403 bool setNominalCurrent(int m, const double val) override;
404 bool getPeakCurrent(int m, double *val) override;
405 bool setPeakCurrent(int m, const double val) override;
406 bool getPWM(int m, double* val) override;
407 bool getPWMLimit(int m, double* val) override;
408 bool setPWMLimit(int m, const double val) override;
409 bool getPowerSupplyVoltage(int m, double* val) override;
410
411 // IControlLimits
412 bool setLimits(int axis, double min, double max) override;
413 bool getLimits(int axis, double *min, double *max) override;
414 bool setVelLimits(int axis, double min, double max) override;
415 bool getVelLimits(int axis, double *min, double *max) override;
416
417 // IAxisInfo
418 bool getAxisName(int j, std::string& name) override;
419 bool getJointType(int j, yarp::dev::JointTypeEnum& type) override;
420
421 // IControlCalibration
422 bool calibrateRobot() override;
423 bool abortCalibration() override;
424 bool abortPark() override;
425 bool park(bool wait=true) override;
426 bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override;
427 bool setCalibrationParameters(int j, const CalibrationParameters& params) override;
428 bool calibrationDone(int j) override;
429
430 // ITorqueControl
431 bool getRefTorque(int j, double *t) override;
432 bool getRefTorques(double *t) override;
433 bool setRefTorques(const double *t) override;
434 bool setRefTorque(int j, double v) override;
435 bool setRefTorques(const int n_joint, const int *joints, const double *t) override;
436 bool setMotorTorqueParams(int j, const MotorTorqueParameters params) override;
437 bool getMotorTorqueParams(int j, MotorTorqueParameters *params) override;
438 bool getTorque(int j, double *t) override;
439 bool getTorques(double *t) override;
440 bool getTorqueRange(int j, double *min, double* max) override;
441 bool getTorqueRanges(double *min, double *max) override;
442
443 // IImpedanceControl
444 bool getImpedance(int j, double *stiffness, double *damping) override;
445 bool getImpedanceOffset(int j, double *offset) override;
446 bool setImpedance(int j, double stiffness, double damping) override;
447 bool setImpedanceOffset(int j, double offset) override;
448 bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
449
450 // IControlMode
451 bool getControlMode(int j, int *mode) override;
452 bool getControlModes(int *modes) override;
453 bool getControlModes(const int n_joint, const int *joints, int *modes) override;
454 bool setControlMode(const int j, const int mode) override;
455 bool setControlModes(const int n_joint, const int *joints, int *modes) override;
456 bool setControlModes(int *modes) override;
457
458 // IPositionDirect
459 bool setPosition(int j, double ref) override;
460 bool setPositions(const int n_joint, const int *joints, const double *refs) override;
461 bool setPositions(const double *refs) override;
462 bool getRefPosition(const int joint, double* ref) override;
463 bool getRefPositions(double* refs) override;
464 bool getRefPositions(const int n_joint, const int* joints, double* refs) override;
465
466 // IVelocityControl
467 bool velocityMove(const int n_joint, const int *joints, const double *spds) override;
468 bool getRefVelocity(const int joint, double* vel) override;
469 bool getRefVelocities(double* vels) override;
470 bool getRefVelocities(const int n_joint, const int* joints, double* vels) override;
471
472 // IInteractionMode
474 bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
477 bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
479
480 // IRemoteCalibrator
481 bool isCalibratorDevicePresent(bool *isCalib) override;
482 bool calibrateSingleJoint(int j) override;
483 bool calibrateWholePart() override;
484 bool homingSingleJoint(int j) override;
485 bool homingWholePart() override;
486 bool parkSingleJoint(int j, bool _wait=true) override;
487 bool parkWholePart() override;
488 bool quitCalibrate() override;
489 bool quitPark() override;
490
491 // ICurrentControl
492 bool getRefCurrents(double *t) override;
493 bool getRefCurrent(int j, double *t) override;
494 bool setRefCurrents(const double *refs) override;
495 bool setRefCurrent(int j, double ref) override;
496 bool setRefCurrents(const int n_joint, const int *joints, const double *refs) override;
497 bool getCurrents(double *vals) override;
498 bool getCurrent(int j, double *val) override;
499 bool getCurrentRange(int j, double *min, double *max) override;
500 bool getCurrentRanges(double *min, double *max) override;
501
502 // IPWMControl
503 bool setRefDutyCycle(int j, double v) override;
504 bool setRefDutyCycles(const double *v) override;
505 bool getRefDutyCycle(int j, double *ref) override;
506 bool getRefDutyCycles(double *refs) override;
507 bool getDutyCycle(int j, double *out) override;
508 bool getDutyCycles(double *outs) override;
509};
510
511
512
513#endif // YARP_DEV_REMOTECONTROLBOARD_REMOTECONTROLBOARD_H
float t
define control board standard interfaces
define control board standard interfaces
define control board standard interfaces
contains the definition of a Vector type
remote_controlboard: The client side of the control board, connects to a remote controlboard using th...
bool setPidReferences(const PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool relativeMove(int j, double delta) override
Set relative position.
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 getRefSpeeds(const int n_joint, const int *joints, double *spds) override
Get reference speed of all joints.
bool get1V1I1B(int v, int j, bool &val)
Helper method used to get a double value from the remote peer.
bool quitCalibrate() override
quitCalibrate: interrupt the calibration procedure
bool getRefPositions(double *refs) override
Get the last position reference for all axes.
yarp::os::PortReaderBuffer< yarp::sig::Vector > state_buffer
bool get1V1I1IA1B(int v, const int len, const int *val1, bool &retVal)
bool open(Searchable &config) override
Open the DeviceDriver.
bool getEncoder(int j, double *v) override
Read the value of an encoder.
bool send2V1I(int v1, int v2, int axis)
bool setPositions(const int n_joint, const int *joints, const double *refs) override
Set new reference point for all axes.
yarp::dev::impl::jointData last_wholePart
bool setControlMode(const int j, const int mode) override
Set the current control mode.
bool isPidEnabled(const PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid.
~RemoteControlBoard() override=default
bool getPeakCurrent(int m, double *val) override
bool getLimits(int axis, double *min, double *max) override
Get the software limits for a particular axis.
RemoteControlBoard(const RemoteControlBoard &)=delete
bool getPWM(int m, double *val) override
yarp::os::PortWriterBuffer< CommandMessage > command_buffer
bool get1VDA(int v, double *val)
Helper method to get an array of double from the remote peer.
bool set2V1DA(int v1, int v2, const double *val)
bool get1V1I(int code, int &v) const
Send a GET command expecting an integer value in return.
bool getNominalCurrent(int m, double *val) override
bool resetPid(const PidControlTypeEnum &pidtype, int j) override
Reset the controller of a given joint, usually sets the current status of the joint as the reference ...
bool setPeakCurrent(int m, const double val) override
bool getPidOutputs(const PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool send2V(int v1, int v2)
bool set1V1I(int code, int v)
Send a SET command with an additional integer valued variable and then wait for a reply.
bool setInteractionMode(int axis, yarp::dev::InteractionModeEnum mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
bool getTemperatureLimit(int m, double *val) override
Retreives the current temperature limit for a specific motor.
bool getPidError(const PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
bool getPidReference(const PidControlTypeEnum &pidtype, int j, double *ref) override
Get the current reference of the pid controller for a specific joint.
bool homingSingleJoint(int j) override
homingSingleJoint: call the homing procedure for a single joint
bool checkMotionDone(int j, bool *flag) override
Check if the current trajectory is terminated.
bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override
Gets number of counts per revolution for motor encoder m.
bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
ProtocolVersion protocolVersion
bool set2V1I(int v1, int v2, int axis)
bool setRefDutyCycle(int j, double v) override
Sets the reference dutycycle to a single motor.
bool getRefAccelerations(const int n_joint, const int *joints, double *accs) override
Get reference acceleration for a joint.
bool setPidErrorLimit(const 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
bool getPowerSupplyVoltage(int m, double *val) override
bool getRefVelocity(const int joint, double *vel) override
Get the last reference speed set by velocityMove for single joint.
bool getPidOutput(const PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool get1V1I1IA1DA(int v, const int len, const int *val1, double *val2)
bool get1V1DA(int v1, double *val)
Helper method to get an array of double from the remote peer.
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 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 getRefCurrent(int j, double *t) override
Get the reference value of the current for a single motor.
bool getEncoders(double *encs) override
Read the position of all axes.
bool get1V1I1S(int code, int j, std::string &name)
bool set1V(int code)
Send a SET command without parameters and wait for a reply.
Stamp getLastInputStamp() override
Get the time stamp for the last read data.
bool getMotorEncoder(int j, double *v) override
Read the value of a motor encoder.
bool getTemperature(int m, double *val) override
Get temperature of a motor.
bool setPidReference(const PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool setImpedance(int j, double stiffness, double damping) override
Set current impedance gains (stiffness,damping) for a specific joint.
RemoteControlBoard & operator=(const RemoteControlBoard &)=delete
bool getMotorEncoderTimed(int j, double *v, double *t) override
Read the instantaneous position of a motor encoder.
bool getDutyCycles(double *outs) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool setRefCurrent(int j, double ref) override
Set the reference value of the current for a single motor.
DiagnosticThread * diagnosticThread
bool setControlModes(const int n_joint, const int *joints, int *modes) override
Set the current control mode for a subset of axes.
bool setPid(const PidControlTypeEnum &pidtype, int j, const Pid &pid) override
Set new pid value for a joint axis.
bool set1V1I2D(int code, int j, double val1, double val2)
bool getPidErrors(const PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool close() override
Close the device driver and stop the port connections.
bool parkSingleJoint(int j, bool _wait=true) override
parkSingleJoint(): start the parking procedure for the single joint
bool setMotorEncoders(const double *vals) override
Set the value of all motor encoders.
yarp::dev::impl::jointData last_singleJoint
bool getTargetPositions(double *refs) override
Get the last position reference for all axes.
RemoteControlBoard(RemoteControlBoard &&)=delete
bool setEncoders(const double *vals) override
Set the value of all encoders.
bool set1VDA(int v, const double *val)
Helper method used to set an array of double to all axes.
bool getPid(const PidControlTypeEnum &pidtype, int j, Pid *pid) override
Get current pid value for a specific joint.
bool setPosition(int j, double ref) override
Set new position for a single axis.
bool get2V1I2D(int v1, int v2, int j, double *val1, double *val2)
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
bool resetMotorEncoder(int j) override
Reset motor encoder, single motor.
bool getEncoderSpeed(int j, double *sp) override
Read the istantaneous speed of an axis.
bool setGearboxRatio(int m, const double val) override
Set the gearbox ratio for a specific motor.
bool resetMotorEncoders() override
Reset motor encoders.
bool getCurrentRanges(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool getAmpStatus(int *st) override
bool setRefTorque(int j, double v) override
Set the reference value of the torque for a given joint.
bool enablePid(const 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 getImpedance(int j, double *stiffness, double *damping) override
Get current impedance gains (stiffness,damping,offset) for a specific joint.
bool getPidErrorLimits(const PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool getMotorEncoders(double *encs) override
Read the position of all motor encoders.
bool setPids(const PidControlTypeEnum &pidtype, const Pid *pids) override
Set new pid value on multiple axes.
bool setMotorEncoder(int j, const double val) override
Set the value of the motor encoder for a given motor.
bool velocityMove(int j, double v) override
Start motion at a given speed, single joint.
bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override
bool setPidErrorLimits(const PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
RemoteControlBoard()=default
bool calibrationDone(int j) override
Check if the calibration is terminated, on a particular joint.
bool setPidOffset(const PidControlTypeEnum &pidtype, int j, double v) override
Set offset value for a given controller.
bool get2V1I1D(int v1, int v2, int j, double *val)
bool abortCalibration() override
bool setRefCurrents(const double *refs) override
Set the reference value of the currents for all motors.
bool getMotorEncoderAcceleration(int j, double *acc) override
Read the instantaneous acceleration of a motor encoder.
bool setRefTorques(const double *t) override
Set the reference value of the torque for all joints.
bool getNumberOfMotors(int *num) override
Get the number of available motors.
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 get1VIA(int v, int *val)
Helper method to get an array of integers from the remote peer.
bool set1V1I1IA1DA(int v, const int len, const int *val1, const double *val2)
bool getInteractionMode(int axis, yarp::dev::InteractionModeEnum *mode) override
Get the current interaction mode of the robot, values can be stiff or compliant.
bool getCurrentRange(int j, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool getEncoderAcceleration(int j, double *acc) override
Read the instantaneous acceleration of an axis.
RemoteControlBoard & operator=(RemoteControlBoard &&)=delete
bool get1V1B(int v, bool &val)
bool getVelLimits(int axis, double *min, double *max) override
Get the software speed limits for a particular axis.
bool setEncoder(int j, double val) override
Set the value of the encoder for a given joint.
bool send1V1I(int v, int axis)
bool get1V1I2D(int code, int axis, double *v1, double *v2)
bool resetEncoders() override
Reset encoders.
bool checkProtocolVersion(bool ignore)
bool setImpedanceOffset(int j, double offset) override
Set current force Offset for a specific joint.
bool get2V1I1IA1DA(int v1, int v2, const int n_joints, const int *joints, double *retVals, std::string functionName="")
bool getGearboxRatio(int m, double *val) override
Get the gearbox ratio for a specific motor.
bool getRefAcceleration(int j, double *acc) override
Get reference acceleration for a joint.
bool getMaxCurrent(int j, double *v) override
Returns the maximum electric current allowed for a given motor.
bool set2V2DA(int v1, int v2, const double *val1, const double *val2)
bool get2V1DA(int v1, int v2, double *val)
Helper method to get an array of double from the remote peer.
bool setRefAccelerations(const int n_joint, const int *joints, const double *accs) override
Set reference acceleration on all joints.
bool setNominalCurrent(int m, const double val) override
bool getMotorTorqueParams(int j, MotorTorqueParameters *params) override
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool getRefTorques(double *t) override
Get the reference value of the torque for all joints.
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 getRemoteVariable(std::string key, yarp::os::Bottle &val) override
bool getRefDutyCycles(double *refs) override
Gets the last reference sent using the setRefDutyCycles function.
bool set1V2D(int code, double v)
Send a SET command and an additional double valued variable and then wait for a reply.
bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override
bool getMotorEncoderSpeed(int j, double *sp) override
Read the istantaneous speed of a motor encoder.
bool getTemperatures(double *vals) override
Get temperature of all the motors.
bool get2V2DA(int v1, int v2, double *val1, double *val2)
bool getLastJointFault(int j, int &fault, std::string &message) override
bool get1V1D(int code, double &v) const
Send a GET command expecting a double value in return.
yarp::os::Port command_p
bool setRefSpeeds(const int n_joint, const int *joints, const double *spds) override
Set reference speed on all joints.
bool getControlMode(int j, int *mode) override
Get the current control mode.
bool isCalibratorDevicePresent(bool *isCalib) override
isCalibratorDevicePresent: check if a calibrator device has been set
bool homingWholePart() override
homingWholePart: call the homing procedure for a the whole part/device
bool set2V1I1D(int v1, int v2, int axis, double val)
bool parkWholePart() override
parkWholePart: start the parking procedure for the whole part
bool calibrateRobot() override
Calibrate robot by using an external calibrator.
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
bool getMotorEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all motor encoders.
bool resetEncoder(int j) override
Reset encoder, single joint.
bool getDutyCycle(int j, double *out) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool getTargetPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool send3V1I(int v1, int v2, int v3, int j)
bool getRefVelocities(double *vels) override
Get the last reference speed set by velocityMove for all joints.
bool getCurrent(int j, double *val) override
bool getAxes(int *ax) override
Get the number of controlled axes.
StateExtendedInputPort extendedIntputStatePort
bool getPidErrorLimit(const PidControlTypeEnum &pidtype, int j, double *limit) override
Get the error limit for the controller on a specific joint.
bool stop() override
Stop motion, multiple joints.
bool setPWMLimit(int m, const double val) override
bool getRefSpeed(int j, double *ref) override
Get reference speed for a joint.
bool getRefPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool set1V1I1D(int code, int j, double val)
Helper method to set a double value to a single axis.
bool getEncoderTimed(int j, double *v, double *t) override
Read the instantaneous acceleration of all axes.
bool setCalibrationParameters(int j, const CalibrationParameters &params) override
Start calibration, this method is very often platform specific.
bool getRefTorque(int j, double *t) override
Get the reference value of the torque for a given joint.
bool setTemperatureLimit(int m, const double val) override
Set the temperature limit for a specific motor.
bool setValWithPidType(int voc, PidControlTypeEnum type, int axis, double val)
bool calibrateSingleJoint(int j) override
calibrateSingleJoint: call the calibration procedure for the single joint
bool enableAmp(int j) override
Enable the amplifier on a specific joint.
bool getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getTorqueRanges(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
bool park(bool wait=true) override
bool setRefAcceleration(int j, double acc) override
Set reference acceleration for a joint.
bool getRefDutyCycle(int j, double *ref) override
Gets the last reference sent using the setRefDutyCycle function.
bool getMotorEncodersTimed(double *encs, double *ts) override
Read the instantaneous position of all motor encoders.
bool getImpedanceOffset(int j, double *offset) override
Get current force Offset for a specific joint.
bool getValWithPidType(int voc, PidControlTypeEnum type, int j, double *val)
bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override
Start calibration, this method is very often platform specific.
bool getNumberOfMotorEncoders(int *num) override
Get the number of available motor encoders.
bool disablePid(const PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all motor encoders.
bool getPWMLimit(int m, double *val) override
bool getCurrents(double *vals) override
bool disableAmp(int j) override
Disable the amplifier on a specific joint.
bool setVelLimits(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 getEncodersTimed(double *encs, double *ts) override
Read the instantaneous acceleration of all axes.
bool getPids(const PidControlTypeEnum &pidtype, Pid *pids) override
Get current pid value for a specific joint.
bool get1V1I1D(int v, int j, double *val)
Helper method used to get a double value from the remote peer.
bool getEncoderAccelerations(double *accs) override
Read the instantaneous acceleration of all axes.
bool setMotorTorqueParams(int j, const MotorTorqueParameters params) override
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool setLimits(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 getTorqueRange(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool setRefDutyCycles(const double *v) override
Sets the reference dutycycle for all the motors.
bool positionMove(int j, double ref) override
Set new reference point for a single axis.
bool quitPark() override
quitPark: interrupt the park procedure
bool get1V1I1I(int v, int j, int *val)
Helper method used to get an integer value from the remote peer.
bool getAxisName(int j, std::string &name) override
bool getPidReferences(const PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool getRefCurrents(double *t) override
Get the reference value of the currents for all motors.
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 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 mini-server for performing network communication in the background.
A mini-server for network communication.
Definition Port.h:46
A base class for nested structures that can be searched.
Definition Searchable.h:56
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
PidControlTypeEnum
Definition PidEnums.h:15