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"
38
40{
41 int major{0};
42 int minor{0};
43 int tweak{0};
44};
45
47
48
66 public yarp::dev::IMotor,
84{
85protected:
89
94
95 // Buffer associated to the extendedOutputStatePort port; in this case we will use the type generated
96 // from the YARP .thrift file
97// yarp::os::PortReaderBuffer<jointData> extendedInputState_buffer; // Buffer storing new data
98 StateExtendedInputPort extendedIntputStatePort; // Buffered port storing new data
100 yarp::dev::impl::jointData last_singleJoint; // tmp to store last received data for a particular joint
101// yarp::os::Port extendedIntputStatePort; // Port /stateExt:i reading the state of the joints
102 yarp::dev::impl::jointData last_wholePart; // tmp to store last received data for whole part
103
104 mutable Stamp lastStamp; //this is shared among all calls that read encoders
105 size_t nj{0};
106 bool njIsKnown{false};
107
109
110 // Check for number of joints, if needed.
111 // This is to allow for delayed connection to the remote control board.
112 bool isLive();
113
114 bool checkProtocolVersion(bool ignore);
115
116 bool send1V(int v);
117 bool send2V(int v1, int v2);
118 bool send2V1I(int v1, int v2, int axis);
119 bool send1V1I(int v, int axis);
120 bool send3V1I(int v1, int v2, int v3, int j);
121
127 bool set1V(int code);
128
136 bool set1V2D(int code, double v);
137
145 bool set1V1I(int code, int v);
146
153 bool get1V1D(int code, double& v) const;
154
161 bool get1V1I(int code, int& v) const;
162
170 bool set1V1I1D(int code, int j, double val);
171
172 bool set1V1I2D(int code, int j, double val1, double val2);
173
180 bool set1VDA(int v, const double *val);
181 bool set2V1DA(int v1, int v2, const double *val);
182 bool set2V2DA(int v1, int v2, const double *val1, const double *val2);
183 bool set1V1I1IA1DA(int v, const int len, const int *val1, const double *val2);
184 bool set2V1I1D(int v1, int v2, int axis, double val);
185 bool setValWithPidType(int voc, PidControlTypeEnum type, int axis, double val);
186 bool setValWithPidType(int voc, PidControlTypeEnum type, const double* val_arr);
187 bool getValWithPidType(int voc, PidControlTypeEnum type, int j, double *val);
188 bool getValWithPidType(int voc, PidControlTypeEnum type, double *val);
189 bool set2V1I(int v1, int v2, int axis);
190
198 bool get1V1I1D(int v, int j, double *val);
199
207 bool get1V1I1I(int v, int j, int *val);
208 bool get2V1I1D(int v1, int v2, int j, double *val);
209 bool get2V1I2D(int v1, int v2, int j, double *val1, double *val2);
210 bool get1V1I2D(int code, int axis, double *v1, double *v2);
211
219 bool get1V1I1B(int v, int j, bool &val);
220 bool get1V1I1IA1B(int v, const int len, const int *val1, bool &retVal);
221 bool get2V1I1IA1DA(int v1, int v2, const int n_joints, const int *joints, double *retVals, std::string functionName = "");
222 bool get1V1B(int v, bool &val);
223
230 bool get1VIA(int v, int *val);
231
238 bool get1VDA(int v, double *val);
239
246 bool get1V1DA(int v1, double *val);
247
255 bool get2V1DA(int v1, int v2, double *val);
256
257 bool get2V2DA(int v1, int v2, double *val1, double *val2);
258
259 bool get1V1I1S(int code, int j, std::string &name);
260
261 bool get1V1I1IA1DA(int v, const int len, const int *val1, double *val2);
262
263public:
269 ~RemoteControlBoard() override = default;
270
271 bool open(Searchable& config) override;
272
277 bool close() override;
278
279 bool getAxes(int *ax) override;
280
281 // IPidControl
282 bool setPid(const PidControlTypeEnum& pidtype, int j, const Pid &pid) override;
283 bool setPids(const PidControlTypeEnum& pidtype, const Pid *pids) override;
284 bool setPidReference(const PidControlTypeEnum& pidtype, int j, double ref) override;
285 bool setPidReferences(const PidControlTypeEnum& pidtype, const double *refs) override;
286 bool setPidErrorLimit(const PidControlTypeEnum& pidtype, int j, double limit) override;
287 bool setPidErrorLimits(const PidControlTypeEnum& pidtype, const double *limits) override;
288 bool getPidError(const PidControlTypeEnum& pidtype, int j, double *err) override;
289 bool getPidErrors(const PidControlTypeEnum& pidtype, double *errs) override;
290 bool getPid(const PidControlTypeEnum& pidtype, int j, Pid *pid) override;
291 bool getPids(const PidControlTypeEnum& pidtype, Pid *pids) override;
292 bool getPidReference(const PidControlTypeEnum& pidtype, int j, double *ref) override;
293 bool getPidReferences(const PidControlTypeEnum& pidtype, double *refs) override;
294 bool getPidErrorLimit(const PidControlTypeEnum& pidtype, int j, double *limit) override;
295 bool getPidErrorLimits(const PidControlTypeEnum& pidtype, double *limits) override;
296 bool resetPid(const PidControlTypeEnum& pidtype, int j) override;
297 bool disablePid(const PidControlTypeEnum& pidtype, int j) override;
298 bool enablePid(const PidControlTypeEnum& pidtype, int j) override;
299 bool isPidEnabled(const PidControlTypeEnum& pidtype, int j, bool* enabled) override;
300 bool getPidOutput(const PidControlTypeEnum& pidtype, int j, double *out) override;
301 bool getPidOutputs(const PidControlTypeEnum& pidtype, double *outs) override;
302 bool setPidOffset(const PidControlTypeEnum& pidtype, int j, double v) override;
303
304 // IEncoder
305 bool resetEncoder(int j) override;
306 bool resetEncoders() override;
307 bool setEncoder(int j, double val) override;
308 bool setEncoders(const double *vals) override;
309 bool getEncoder(int j, double *v) override;
310 bool getEncoderTimed(int j, double *v, double *t) override;
311 bool getEncoders(double *encs) override;
312 bool getEncodersTimed(double *encs, double *ts) override;
313 bool getEncoderSpeed(int j, double *sp) override;
314 bool getEncoderSpeeds(double *spds) override;
315 bool getEncoderAcceleration(int j, double *acc) override;
316 bool getEncoderAccelerations(double *accs) override;
317
318 // IRemoteVariable
319 bool getRemoteVariable(std::string key, yarp::os::Bottle& val) override;
320 bool setRemoteVariable(std::string key, const yarp::os::Bottle& val) override;
322
323 // IMotor
324 bool getNumberOfMotors(int *num) override;
325 bool getTemperature(int m, double* val) override;
326 bool getTemperatures(double *vals) override;
327 bool getTemperatureLimit (int m, double* val) override;
328 bool setTemperatureLimit (int m, const double val) override;
329 bool getGearboxRatio(int m, double* val) override;
330 bool setGearboxRatio(int m, const double val) override;
331
332 // IMotorEncoder
333 bool resetMotorEncoder(int j) override;
334 bool resetMotorEncoders() override;
335 bool setMotorEncoder(int j, const double val) override;
336 bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override;
337 bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override;
338 bool setMotorEncoders(const double *vals) override;
339 bool getMotorEncoder(int j, double *v) override;
340 bool getMotorEncoderTimed(int j, double *v, double *t) override;
341 bool getMotorEncoders(double *encs) override;
342 bool getMotorEncodersTimed(double *encs, double *ts) override;
343 bool getMotorEncoderSpeed(int j, double *sp) override;
344 bool getMotorEncoderSpeeds(double *spds) override;
345 bool getMotorEncoderAcceleration(int j, double *acc) override;
346 bool getMotorEncoderAccelerations(double *accs) override;
347 bool getNumberOfMotorEncoders(int *num) override;
348
349 // IPreciselyTimed
350 Stamp getLastInputStamp() override;
351
352 // IPositionControl
353 bool positionMove(int j, double ref) override;
354 bool positionMove(const int n_joint, const int *joints, const double *refs) override;
355 bool positionMove(const double *refs) override;
356 bool getTargetPosition(const int joint, double *ref) override;
357 bool getTargetPositions(double *refs) override;
358 bool getTargetPositions(const int n_joint, const int *joints, double *refs) override;
359 bool relativeMove(int j, double delta) override;
360 bool relativeMove(const int n_joint, const int *joints, const double *refs) override;
361 bool relativeMove(const double *deltas) override;
362 bool checkMotionDone(int j, bool *flag) override;
363 bool checkMotionDone(const int n_joint, const int *joints, bool *flag) override;
364 bool checkMotionDone(bool *flag) override;
365 bool setRefSpeed(int j, double sp) override;
366 bool setRefSpeeds(const int n_joint, const int *joints, const double *spds) override;
367 bool setRefSpeeds(const double *spds) override;
368 bool setRefAcceleration(int j, double acc) override;
369 bool setRefAccelerations(const int n_joint, const int *joints, const double *accs) override;
370 bool setRefAccelerations(const double *accs) override;
371 bool getRefSpeed(int j, double *ref) override;
372 bool getRefSpeeds(const int n_joint, const int *joints, double *spds) override;
373 bool getRefSpeeds(double *spds) override;
374 bool getRefAcceleration(int j, double *acc) override;
375 bool getRefAccelerations(const int n_joint, const int *joints, double *accs) override;
376 bool getRefAccelerations(double *accs) override;
377 bool stop(int j) override;
378 bool stop(const int len, const int *val1) override;
379 bool stop() override;
380
381 // IJointFault
382 bool getLastJointFault(int j, int& fault, std::string& message) override;
383
384 // IVelocityControl
385 bool velocityMove(int j, double v) override;
386 bool velocityMove(const double *v) override;
387
388 // IAmplifierControl
389 bool enableAmp(int j) override;
390 bool disableAmp(int j) override;
391 bool getAmpStatus(int *st) override;
392 bool getAmpStatus(int j, int *st) override;
393 bool setMaxCurrent(int j, double v) override;
394 bool getMaxCurrent(int j, double *v) override;
395 bool getNominalCurrent(int m, double *val) override;
396 bool setNominalCurrent(int m, const double val) override;
397 bool getPeakCurrent(int m, double *val) override;
398 bool setPeakCurrent(int m, const double val) override;
399 bool getPWM(int m, double* val) override;
400 bool getPWMLimit(int m, double* val) override;
401 bool setPWMLimit(int m, const double val) override;
402 bool getPowerSupplyVoltage(int m, double* val) override;
403
404 // IControlLimits
405 bool setLimits(int axis, double min, double max) override;
406 bool getLimits(int axis, double *min, double *max) override;
407 bool setVelLimits(int axis, double min, double max) override;
408 bool getVelLimits(int axis, double *min, double *max) override;
409
410 // IAxisInfo
411 bool getAxisName(int j, std::string& name) override;
412 bool getJointType(int j, yarp::dev::JointTypeEnum& type) override;
413
414 // IControlCalibration
415 bool calibrateRobot() override;
416 bool abortCalibration() override;
417 bool abortPark() override;
418 bool park(bool wait=true) override;
419 bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override;
420 bool setCalibrationParameters(int j, const CalibrationParameters& params) override;
421 bool calibrationDone(int j) override;
422
423 // ITorqueControl
424 bool getRefTorque(int j, double *t) override;
425 bool getRefTorques(double *t) override;
426 bool setRefTorques(const double *t) override;
427 bool setRefTorque(int j, double v) override;
428 bool setRefTorques(const int n_joint, const int *joints, const double *t) override;
429 bool setMotorTorqueParams(int j, const MotorTorqueParameters params) override;
430 bool getMotorTorqueParams(int j, MotorTorqueParameters *params) override;
431 bool getTorque(int j, double *t) override;
432 bool getTorques(double *t) override;
433 bool getTorqueRange(int j, double *min, double* max) override;
434 bool getTorqueRanges(double *min, double *max) override;
435
436 // IImpedanceControl
437 bool getImpedance(int j, double *stiffness, double *damping) override;
438 bool getImpedanceOffset(int j, double *offset) override;
439 bool setImpedance(int j, double stiffness, double damping) override;
440 bool setImpedanceOffset(int j, double offset) override;
441 bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
442
443 // IControlMode
444 bool getControlMode(int j, int *mode) override;
445 bool getControlModes(int *modes) override;
446 bool getControlModes(const int n_joint, const int *joints, int *modes) override;
447 bool setControlMode(const int j, const int mode) override;
448 bool setControlModes(const int n_joint, const int *joints, int *modes) override;
449 bool setControlModes(int *modes) override;
450
451 // IPositionDirect
452 bool setPosition(int j, double ref) override;
453 bool setPositions(const int n_joint, const int *joints, const double *refs) override;
454 bool setPositions(const double *refs) override;
455 bool getRefPosition(const int joint, double* ref) override;
456 bool getRefPositions(double* refs) override;
457 bool getRefPositions(const int n_joint, const int* joints, double* refs) override;
458
459 // IVelocityControl
460 bool velocityMove(const int n_joint, const int *joints, const double *spds) override;
461 bool getRefVelocity(const int joint, double* vel) override;
462 bool getRefVelocities(double* vels) override;
463 bool getRefVelocities(const int n_joint, const int* joints, double* vels) override;
464
465 // IInteractionMode
467 bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
470 bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
472
473 // IRemoteCalibrator
474 bool isCalibratorDevicePresent(bool *isCalib) override;
475 bool calibrateSingleJoint(int j) override;
476 bool calibrateWholePart() override;
477 bool homingSingleJoint(int j) override;
478 bool homingWholePart() override;
479 bool parkSingleJoint(int j, bool _wait=true) override;
480 bool parkWholePart() override;
481 bool quitCalibrate() override;
482 bool quitPark() override;
483
484 // ICurrentControl
485 bool getRefCurrents(double *t) override;
486 bool getRefCurrent(int j, double *t) override;
487 bool setRefCurrents(const double *refs) override;
488 bool setRefCurrent(int j, double ref) override;
489 bool setRefCurrents(const int n_joint, const int *joints, const double *refs) override;
490 bool getCurrents(double *vals) override;
491 bool getCurrent(int j, double *val) override;
492 bool getCurrentRange(int j, double *min, double *max) override;
493 bool getCurrentRanges(double *min, double *max) override;
494
495 // IPWMControl
496 bool setRefDutyCycle(int j, double v) override;
497 bool setRefDutyCycles(const double *v) override;
498 bool getRefDutyCycle(int j, double *ref) override;
499 bool getRefDutyCycles(double *refs) override;
500 bool getDutyCycle(int j, double *out) override;
501 bool getDutyCycles(double *outs) override;
502};
503
504
505
506#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
This class is the parameters parser for class RemoteControlBoard.
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:31
An abstraction for a time stamp and/or sequence number.
Definition Stamp.h:21
PidControlTypeEnum
Definition PidEnums.h:15