YARP
Yet Another Robot Platform
ControlBoardWrapper.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H
10 #define YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H
11 
12 
13 // ControlBoardWrapper
14 // A modified version of the remote control board class
15 // which remaps joints, it can also merge networks into a single part.
16 //
17 
18 #include <yarp/os/PortablePair.h>
19 #include <yarp/os/BufferedPort.h>
20 #include <yarp/os/Time.h>
21 #include <yarp/os/Network.h>
22 #include <yarp/os/PeriodicThread.h>
23 #include <yarp/os/Stamp.h>
24 #include <yarp/os/Vocab.h>
25 
27 #include <yarp/dev/PolyDriver.h>
30 #include <yarp/sig/Vector.h>
33 
34 #include <mutex>
35 #include <string>
36 #include <vector>
37 
38 #include <yarp/dev/impl/jointData.h> // struct for YARP extended port
39 
40 #include "SubDevice.h"
42 #include "RPCMessagesParser.h"
43 
44 // ROS state publisher
45 #include <yarp/os/Node.h>
46 #include <yarp/os/Publisher.h>
49 
50 #ifdef MSVC
51  #pragma warning(disable:4355)
52 #endif
53 
54 #define PROTOCOL_VERSION_MAJOR 1
55 #define PROTOCOL_VERSION_MINOR 9
56 #define PROTOCOL_VERSION_TWEAK 0
57 
58 /*
59  * To optimize memory allocation, for group of joints we can have one mem reserver for rpc port
60  * and on e for streaming. The size could be numOfSubDevices*maxNumOfjointForSubdevice.
61  * (we could also use the actual joint number for each subdevice using a for loop). TODO
62  */
63 
64 class CommandsHelper;
65 class SubDevice;
66 class WrappedDevice;
67 
69 {
70 public:
71  int deviceNum{0};
73 
74  int *subdev_jointsVectorLen{nullptr}; // number of joints belonging to each subdevice
75  int **jointNumbers{nullptr};
76  int **modes{nullptr};
77  double **values{nullptr};
78  SubDevice **subdevices_p{nullptr};
79 
80  MultiJointData() = default;
81 
82  void resize(int _deviceNum, int _maxJointsNumForDevice, WrappedDevice *_device)
83  {
84  deviceNum = _deviceNum;
85  maxJointsNumForDevice = _maxJointsNumForDevice;
87  jointNumbers = new int *[deviceNum]; // alloc a vector of pointers
88  jointNumbers[0] = new int[deviceNum * _maxJointsNumForDevice]; // alloc real memory for data
89 
90  modes = new int *[deviceNum]; // alloc a vector of pointers
91  modes[0] = new int[deviceNum * _maxJointsNumForDevice]; // alloc real memory for data
92 
93  values = new double *[deviceNum]; // alloc a vector of pointers
94  values[0] = new double[deviceNum * _maxJointsNumForDevice]; // alloc real memory for data
95 
97  subdevices_p[0] = _device->getSubdevice(0);
98 
99  for (int i = 1; i < deviceNum; i++)
100  {
101  jointNumbers[i] = jointNumbers[i-1] + _maxJointsNumForDevice; // set pointer to correct location
102  values [i] = values[i-1] + _maxJointsNumForDevice; // set pointer to correct location
103  modes [i] = modes[i-1] + _maxJointsNumForDevice; // set pointer to correct location
104  subdevices_p[i] = _device->getSubdevice(i);
105  }
106  }
107 
108  void destroy()
109  {
110  // release matrix memory
111  delete[] jointNumbers[0];
112  delete[] values[0];
113  delete[] modes[0];
114 
115  // release vector of pointers
116  delete[] jointNumbers;
117  delete[] values;
118  delete[] modes;
119 
120  // delete other vectors
121  delete[] subdev_jointsVectorLen;
122  delete[] subdevices_p;
123  }
124 };
125 
228  public yarp::dev::IPidControl,
233  public yarp::dev::IMotor,
243  public yarp::dev::IAxisInfo,
247  public yarp::dev::IPWMControl,
249 {
250 private:
251  std::string rootName;
252  WrappedDevice device;
253 
254  bool checkPortName(yarp::os::Searchable &params);
255 
257 
258  yarp::os::BufferedPort<yarp::sig::Vector> outputPositionStatePort; // Port /state:o streaming out the encoder positions
259  yarp::os::BufferedPort<CommandMessage> inputStreamingPort; // Input streaming port for high frequency commands
260  yarp::os::Port inputRPCPort; // Input RPC port for set/get remote calls
261  yarp::os::Stamp time; // envelope to attach to the state port
262  yarp::sig::Vector times; // time for each joint
263  std::mutex timeMutex;
264 
265  // Buffer associated to the extendedOutputStatePort port; in this case we will use the type generated
266  // from the YARP .thrift file
268  yarp::os::Port extendedOutputStatePort; // Port /stateExt:o streaming out the struct with the robot data
269 
270  // ROS state publisher
271  ROSTopicUsageType useROS; // decide if open ROS topic or not
272  std::vector<std::string> jointNames; // name of the joints
273  std::string rosNodeName; // name of the rosNode
274  std::string rosTopicName; // name of the rosTopic
275  yarp::os::Node *rosNode; // add a ROS node
276  yarp::os::NetUint32 rosMsgCounter; // incremental counter in the ROS message
277  yarp::os::PortWriterBuffer<yarp::rosmsg::sensor_msgs::JointState> rosOutputState_buffer; // Buffer associated to the ROS topic
278  yarp::os::Publisher<yarp::rosmsg::sensor_msgs::JointState> rosPublisherPort; // Dedicated ROS topic publisher
279 
280  yarp::os::PortReaderBuffer<yarp::os::Bottle> inputRPC_buffer; // Buffer associated to the inputRPCPort port
281  RPCMessagesParser RPC_parser; // Message parser associated to the inputRPCPort port
282  StreamingMessagesParser streaming_parser; // Message parser associated to the inputStreamingPort port
283 
284 
285  // RPC calls are concurrent from multiple clients, data used inside the calls has to be protected
286  std::mutex rpcDataMutex; // mutex to avoid concurrency between more clients using rppc port
287  MultiJointData rpcData; // Structure used to re-arrange data from "multiple_joints" calls.
288 
289  std::string partName; // to open ports and print more detailed debug messages
290 
291  int controlledJoints;
292  int base; // to be removed
293  int top; // to be removed
294  double period; // thread rate for publishing data
295  bool _verb; // make it work and propagate to subdevice if --subdevice option is used
296 
297  yarp::os::Bottle getOptions();
298  bool updateAxisName();
299  bool checkROSParams(yarp::os::Searchable &config);
300  bool initialize_ROS();
301  bool initialize_YARP(yarp::os::Searchable &prop);
302  void cleanup_yarpPorts();
303 
304  // Default usage
305  // Open the wrapper only, the attach method needs to be called before using it
306  bool openDeferredAttach(yarp::os::Property& prop);
307 
308  // For the simulator, if a subdevice parameter is given to the wrapper, it will
309  // open it and attach to it immediately.
310  yarp::dev::PolyDriver *subDeviceOwned;
311  bool openAndAttachSubDevice(yarp::os::Property& prop);
312 
313  bool ownDevices;
314  inline void printError(std::string func_name, std::string info, bool result)
315  {
316  //If result is false, this means that en error occurred in function named func_name, otherwise means that the device doesn't implement the interface to witch func_name belongs to.
317  // if(false == result)
318  // yCError(CONTROLBOARDREMAPPER) << "CBW(" << partName << "): " << func_name.c_str() << " on device" << info.c_str() << " returns false";
319  //Commented in order to maintain the old behaviour (none message appear if device desn't implement the interface)
320  //else
321  // yCError(CONTROLBOARDREMAPPER) << "CBW(" << partName << "): " << func_name.c_str() << " on device" << info.c_str() << ": the interface is not available.";
322  }
323 
324  void calculateMaxNumOfJointsInDevices();
325 
326 public:
333 
338  bool verbose() const
339  {
340  return _verb;
341  }
342 
343  /* Return id of this device */
344  std::string getId()
345  {
346  return partName;
347  }
348 
353  bool close() override;
354 
355 
366  bool open(yarp::os::Searchable& prop) override;
367 
368  bool detachAll() override;
369 
370  bool attachAll(const yarp::dev::PolyDriverList &l) override;
371 
375  void run() override;
376 
377  /* IPidControl
378  These methods are documented by Doxygen in IPidControl.h*/
379  bool setPid(const yarp::dev::PidControlTypeEnum& pidtype, int j, const yarp::dev::Pid &p) override;
380  bool setPids(const yarp::dev::PidControlTypeEnum& pidtype, const yarp::dev::Pid *ps) override;
381  bool setPidReference(const yarp::dev::PidControlTypeEnum& pidtype, int j, double ref) override;
382  bool setPidReferences(const yarp::dev::PidControlTypeEnum& pidtype, const double *refs) override;
383  bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype, int j, double limit) override;
384  bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype, const double *limits) override;
385  bool getPidError(const yarp::dev::PidControlTypeEnum& pidtype, int j, double *err) override;
386  bool getPidErrors(const yarp::dev::PidControlTypeEnum& pidtype, double *errs) override;
387  bool getPidOutput(const yarp::dev::PidControlTypeEnum& pidtype, int j, double *out) override;
388  bool getPidOutputs(const yarp::dev::PidControlTypeEnum& pidtype, double *outs) override;
389  bool setPidOffset(const yarp::dev::PidControlTypeEnum& pidtype, int j, double v) override;
390  bool getPid(const yarp::dev::PidControlTypeEnum& pidtype, int j, yarp::dev::Pid *p) override;
391  bool getPids(const yarp::dev::PidControlTypeEnum& pidtype, yarp::dev::Pid *pids) override;
392  bool getPidReference(const yarp::dev::PidControlTypeEnum& pidtype, int j, double *ref) override;
393  bool getPidReferences(const yarp::dev::PidControlTypeEnum& pidtype, double *refs) override;
394  bool getPidErrorLimit(const yarp::dev::PidControlTypeEnum& pidtype, int j, double *limit) override;
395  bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum& pidtype, double *limits) override;
396  bool resetPid(const yarp::dev::PidControlTypeEnum& pidtype, int j) override;
397  bool disablePid(const yarp::dev::PidControlTypeEnum& pidtype, int j) override;
398  bool enablePid(const yarp::dev::PidControlTypeEnum& pidtype, int j) override;
399  bool isPidEnabled(const yarp::dev::PidControlTypeEnum& pidtype, int j, bool* enabled) override;
400 
401  /* IPositionControl */
402 
409  bool getAxes(int *ax) override;
410 
417  bool positionMove(int j, double ref) override;
418 
423  bool positionMove(const double *refs) override;
424 
430  bool positionMove(const int n_joints, const int *joints, const double *refs) override;
431 
441  bool getTargetPosition(const int joint, double *ref) override;
442 
452  bool getTargetPositions(double *refs) override;
453 
463  bool getTargetPositions(const int n_joint, const int *joints, double *refs) override;
464 
471  bool relativeMove(int j, double delta) override;
472 
477  bool relativeMove(const double *deltas) override;
478 
484  bool relativeMove(const int n_joints, const int *joints, const double *deltas) override;
485 
492  bool checkMotionDone(int j, bool *flag) override;
499  bool checkMotionDone(bool *flag) override;
500 
507  bool checkMotionDone(const int n_joints, const int *joints, bool *flags) override;
508 
515  bool setRefSpeed(int j, double sp) override;
516 
522  bool setRefSpeeds(const double *spds) override;
523 
530  bool setRefSpeeds(const int n_joints, const int *joints, const double *spds) override;
531 
538  bool setRefAcceleration(int j, double acc) override;
539 
545  bool setRefAccelerations(const double *accs) override;
546 
553  bool setRefAccelerations(const int n_joints, const int *joints, const double *accs) override;
554 
561  bool getRefSpeed(int j, double *ref) override;
562 
568  bool getRefSpeeds(double *spds) override;
569 
576  bool getRefSpeeds(const int n_joints, const int *joints, double *spds) override;
577 
584  bool getRefAcceleration(int j, double *acc) override;
585 
591  bool getRefAccelerations(double *accs) override;
592 
599  bool getRefAccelerations(const int n_joints, const int *joints, double *accs) override;
600 
605  bool stop(int j) override;
606 
611  bool stop() override;
612 
613 
618  bool stop(const int n_joints, const int *joints) override;
619 
620  /* IVelocityControl */
621 
628  bool velocityMove(int j, double v) override;
629 
635  bool velocityMove(const double *v) override;
636 
637  /* IEncoders */
638 
644  bool resetEncoder(int j) override;
645 
650  bool resetEncoders() override;
651 
658  bool setEncoder(int j, double val) override;
659 
665  bool setEncoders(const double *vals) override;
666 
673  bool getEncoder(int j, double *v) override;
674 
680  bool getEncoders(double *encs) override;
681 
682  bool getEncodersTimed(double *encs, double *t) override;
683 
684  bool getEncoderTimed(int j, double *v, double *t) override;
685 
692  bool getEncoderSpeed(int j, double *sp) override;
693 
699  bool getEncoderSpeeds(double *spds) override;
700 
706  bool getEncoderAcceleration(int j, double *acc) override;
712  bool getEncoderAccelerations(double *accs) override;
713 
714  /* IMotorEncoders */
715 
721  bool getNumberOfMotorEncoders(int *num) override;
722 
728  bool resetMotorEncoder(int m) override;
729 
734  bool resetMotorEncoders() override;
735 
742  bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override;
743 
750  bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override;
751 
758  bool setMotorEncoder(int m, const double val) override;
759 
765  bool setMotorEncoders(const double *vals) override;
766 
773  bool getMotorEncoder(int m, double *v) override;
774 
780  bool getMotorEncoders(double *encs) override;
781 
782  bool getMotorEncodersTimed(double *encs, double *t) override;
783 
784  bool getMotorEncoderTimed(int m, double *v, double *t) override;
785 
792  bool getMotorEncoderSpeed(int m, double *sp) override;
793 
799  bool getMotorEncoderSpeeds(double *spds) override;
800 
806  bool getMotorEncoderAcceleration(int m, double *acc) override;
812  bool getMotorEncoderAccelerations(double *accs) override;
813 
814  /* IAmplifierControl */
815 
822  bool enableAmp(int j) override;
823 
829  bool disableAmp(int j) override;
830 
838  bool getAmpStatus(int *st) override;
839 
840  bool getAmpStatus(int j, int *v) override;
841 
847  bool getCurrents(double *vals) override;
848 
855  bool getCurrent(int j, double *val) override;
856 
865  bool setMaxCurrent(int j, double v) override;
866 
875  bool getMaxCurrent(int j, double *v) override;
876 
877  /* Get the the nominal current which can be kept for an indefinite amount of time
878  * without harming the motor. This value is specific for each motor and it is typically
879  * found in its datasheet. The units are Ampere.
880  * This value and the peak current may be used by the firmware to configure
881  * an I2T filter.
882  * @param m motor number
883  * @param val storage for return value. [Ampere]
884  * @return true/false success failure.
885  */
886  bool getNominalCurrent(int m, double *val) override;
887 
888  /* Set the the nominal current which can be kept for an indefinite amount of time
889  * without harming the motor. This value is specific for each motor and it is typically
890  * found in its datasheet. The units are Ampere.
891  * This value and the peak current may be used by the firmware to configure
892  * an I2T filter.
893  * @param m motor number
894  * @param val storage for return value. [Ampere]
895  * @return true/false success failure.
896  */
897  bool setNominalCurrent(int m, const double val) override;
898 
899  /* Get the the peak current which causes damage to the motor if maintained
900  * for a long amount of time.
901  * The value is often found in the motor datasheet, units are Ampere.
902  * This value and the nominal current may be used by the firmware to configure
903  * an I2T filter.
904  * @param m motor number
905  * @param val storage for return value. [Ampere]
906  * @return true/false success failure.
907  */
908  bool getPeakCurrent(int m, double *val) override;
909 
910  /* Set the the peak current. This value which causes damage to the motor if maintained
911  * for a long amount of time.
912  * The value is often found in the motor datasheet, units are Ampere.
913  * This value and the nominal current may be used by the firmware to configure
914  * an I2T filter.
915  * @param m motor number
916  * @param val storage for return value. [Ampere]
917  * @return true/false success failure.
918  */
919  bool setPeakCurrent(int m, const double val) override;
920 
921  /* Get the the current PWM value used to control the motor.
922  * The units are firmware dependent, either machine units or percentage.
923  * @param m motor number
924  * @param val filled with PWM value.
925  * @return true/false success failure.
926  */
927  bool getPWM(int m, double* val) override;
928 
929  /* Get the PWM limit for the given motor.
930  * The units are firmware dependent, either machine units or percentage.
931  * @param m motor number
932  * @param val filled with PWM limit value.
933  * @return true/false success failure.
934  */
935  bool getPWMLimit(int m, double* val) override;
936 
937  /* Set the PWM limit for the given motor.
938  * The units are firmware dependent, either machine units or percentage.
939  * @param m motor number
940  * @param val new value for the PWM limit.
941  * @return true/false success failure.
942  */
943  bool setPWMLimit(int m, const double val) override;
944 
945  /* Get the power source voltage for the given motor in Volt.
946  * @param m motor number
947  * @param val filled with return value.
948  * @return true/false success failure.
949  */
950  bool getPowerSupplyVoltage(int m, double* val) override;
951 
952  /* IControlLimits */
953 
962  bool setLimits(int j, double min, double max) override;
963 
971  bool getLimits(int j, double *min, double *max) override;
972 
981  bool setVelLimits(int j, double min, double max) override;
982 
990  bool getVelLimits(int j, double *min, double *max) override;
991 
992  /* IRemoteVariables */
993 
994  bool getRemoteVariable(std::string key, yarp::os::Bottle& val) override;
995 
996  bool setRemoteVariable(std::string key, const yarp::os::Bottle& val) override;
997 
998  bool getRemoteVariablesList(yarp::os::Bottle* listOfKeys) override;
999 
1000  /* IRemoteCalibrator */
1001 
1002  bool isCalibratorDevicePresent(bool *isCalib) override;
1003 
1009 
1015  bool calibrateSingleJoint(int j) override;
1016 
1021  bool calibrateWholePart() override;
1022 
1028  bool homingSingleJoint(int j) override;
1029 
1034  bool homingWholePart() override;
1035 
1040  bool parkSingleJoint(int j, bool _wait=true) override;
1041 
1046  bool parkWholePart() override;
1047 
1052  bool quitCalibrate() override;
1053 
1058  bool quitPark() override;
1059 
1060  /* IControlCalibration */
1061  bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override;
1062 
1063  bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters& params) override;
1064 
1070  bool calibrationDone(int j) override;
1071 
1072  bool abortPark() override;
1073 
1074  bool abortCalibration() override;
1075 
1076  /* IMotor */
1077  bool getNumberOfMotors (int *num) override;
1078 
1079  bool getTemperature (int m, double* val) override;
1080 
1081  bool getTemperatures (double *vals) override;
1082 
1083  bool getTemperatureLimit (int m, double* val) override;
1084 
1085  bool setTemperatureLimit (int m, const double val) override;
1086 
1087  bool getGearboxRatio(int m, double* val) override;
1088 
1089  bool setGearboxRatio(int m, const double val) override;
1090 
1091  /* IAxisInfo */
1092  bool getAxisName(int j, std::string& name) override;
1093 
1094  bool getJointType(int j, yarp::dev::JointTypeEnum& type) override;
1095 
1096  bool getRefTorques(double *refs) override;
1097 
1098  bool getRefTorque(int j, double *t) override;
1099 
1100  bool setRefTorques(const double *t) override;
1101 
1102  bool setRefTorque(int j, double t) override;
1103 
1104  bool setRefTorques(const int n_joint, const int *joints, const double *t) override;
1105 
1106  bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override;
1107 
1108  bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override;
1109 
1110  bool setImpedance(int j, double stiff, double damp) override;
1111 
1112  bool setImpedanceOffset(int j, double offset) override;
1113 
1114  bool getTorque(int j, double *t) override;
1115 
1116  bool getTorques(double *t) override;
1117 
1118  bool getTorqueRange(int j, double *min, double *max) override;
1119 
1120  bool getTorqueRanges(double *min, double *max) override;
1121 
1122  bool getImpedance(int j, double* stiff, double* damp) override;
1123 
1124  bool getImpedanceOffset(int j, double* offset) override;
1125 
1126  bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override;
1127 
1128  bool getControlMode(int j, int *mode) override;
1129 
1130  bool getControlModes(int *modes) override;
1131 
1132  // iControlMode2
1133  bool getControlModes(const int n_joint, const int *joints, int *modes) override;
1134 
1135  bool setControlMode(const int j, const int mode) override;
1136 
1137  bool setControlModes(const int n_joints, const int *joints, int *modes) override;
1138 
1139  bool setControlModes(int *modes) override;
1140 
1141  // IPositionDirect
1142 
1143  bool setPosition(int j, double ref) override;
1144 
1145  bool setPositions(const int n_joints, const int *joints, const double *dpos) override;
1146 
1147  bool setPositions(const double *refs) override;
1148 
1158  bool getRefPosition(const int joint, double *ref) override;
1159 
1169  bool getRefPositions(double *refs) override;
1170 
1180  bool getRefPositions(const int n_joint, const int *joints, double *refs) override;
1181 
1183 
1184  //
1185  // IVelocityControl2 Interface
1186  //
1187  bool velocityMove(const int n_joints, const int *joints, const double *spds) override;
1188 
1189  bool getRefVelocity(const int joint, double* vel) override;
1190 
1191  bool getRefVelocities(double* vels) override;
1192 
1193  bool getRefVelocities(const int n_joint, const int* joints, double* vels) override;
1194 
1195  bool getInteractionMode(int j, yarp::dev::InteractionModeEnum* mode) override;
1196 
1197  bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
1198 
1200 
1201  bool setInteractionMode(int j, yarp::dev::InteractionModeEnum mode) override;
1202 
1203  bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum* modes) override;
1204 
1206 
1207  //
1208  // IPWMControl Interface
1209  //
1210 
1211  bool setRefDutyCycle(int j, double v) override;
1212  bool setRefDutyCycles(const double *v) override;
1213  bool getRefDutyCycle(int j, double *v) override;
1214  bool getRefDutyCycles(double *v) override;
1215  bool getDutyCycle(int j, double *v) override;
1216  bool getDutyCycles(double *v) override;
1217 
1218  //
1219  // ICurrentControl Interface
1220  //
1221 
1222  //bool getAxes(int *ax) override;
1223  //bool getCurrent(int j, double *t) override;
1224  //bool getCurrents(double *t) override;
1225  bool getCurrentRange(int j, double *min, double *max) override;
1226  bool getCurrentRanges(double *min, double *max) override;
1227  bool setRefCurrents(const double *t) override;
1228  bool setRefCurrent(int j, double t) override;
1229  bool setRefCurrents(const int n_joint, const int *joints, const double *t) override;
1230  bool getRefCurrents(double *t) override;
1231  bool getRefCurrent(int j, double *t) override;
1232 };
1233 
1234 
1235 #endif // YARP_DEV_CONTROLBOARDWRAPPER_CONTROLBOARDWRAPPER_H
define control board standard interfaces
float t
contains the definition of a Vector type
bool getRefDutyCycle(int j, double *v) override
Gets the last reference sent using the setRefDutyCycle function.
bool getImpedance(int j, double *stiff, double *damp) override
Get current impedance gains (stiffness,damping,offset) for a specific joint.
bool getControlMode(int j, int *mode) override
Get the current control mode.
bool getTargetPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool setControlModes(const int n_joints, const int *joints, int *modes) override
Set the current control mode for a subset of axes.
bool open(yarp::os::Searchable &prop) override
Open the device driver.
bool getTemperatures(double *vals) override
Get temperature of all the motors.
bool setEncoders(const double *vals) override
Set the value of all encoders.
bool setGearboxRatio(int m, const double val) override
Set the gearbox ratio for a specific motor.
bool setControlMode(const int j, const int mode) override
Set the current control mode.
bool getPidOutput(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *out) override
Get the output of the controller (e.g.
bool enableAmp(int j) override
Enable the amplifier on a specific joint.
bool getCurrentRanges(double *min, double *max) override
Get the full scale of the current measurements for all motors motor (e.g.
bool getPWMLimit(int m, double *val) override
bool getTorques(double *t) override
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
bool getLimits(int j, double *min, double *max) override
Get the software limits for a particular axis.
bool getAxes(int *ax) override
Get the number of controlled axes.
bool detachAll() override
Detach the object (you must have first called attach).
bool getNominalCurrent(int m, double *val) override
bool setRefCurrent(int j, double t) override
Set the reference value of the current for a single motor.
bool getEncoderTimed(int j, double *v, double *t) override
Read the instantaneous acceleration of all axes.
bool getMotorEncoderAccelerations(double *accs) override
Read the istantaneous acceleration of all axes.
bool getCurrentRange(int j, double *min, double *max) override
Get the full scale of the current measurement for a given motor (e.g.
bool getEncoderAccelerations(double *accs) override
Read the istantaneous acceleration of all axes.
bool setRefSpeed(int j, double sp) override
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
bool disablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Disable the pid computation for a joint.
bool verbose() const
Return the value of the verbose flag.
bool setRefCurrents(const double *t) override
Set the reference value of the currents for all motors.
bool getCurrents(double *vals) override
Read the electric current going to all motors.
bool getMotorEncoders(double *encs) override
Read the position of all axes.
bool getRefVelocity(const int joint, double *vel) override
Get the last reference speed set by velocityMove for single joint.
bool setPidReference(const yarp::dev::PidControlTypeEnum &pidtype, int j, double ref) override
Set the controller reference for a given axis.
bool getPowerSupplyVoltage(int m, double *val) override
bool setRefTorque(int j, double t) override
Set 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 setRefDutyCycles(const double *v) override
Sets the reference dutycycle for all the motors.
bool getTemperatureLimit(int m, double *val) override
Retreives the current temperature limit for a specific motor.
bool relativeMove(int j, double delta) override
Set relative position.
bool getTemperature(int m, double *val) override
Get temperature of a motor.
bool getRefCurrents(double *t) override
Get the reference value of the currents for all motors.
bool setPids(const yarp::dev::PidControlTypeEnum &pidtype, const yarp::dev::Pid *ps) override
Set new pid value on multiple axes.
bool setRefTorques(const double *t) override
Set the reference value of the torque for all joints.
bool calibrateAxisWithParams(int j, unsigned int ui, double v1, double v2, double v3) override
Start calibration, this method is very often platform specific.
bool getMotorEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getPids(const yarp::dev::PidControlTypeEnum &pidtype, yarp::dev::Pid *pids) override
Get current pid value for a specific joint.
bool getRefVelocities(double *vels) override
Get the last reference speed set by velocityMove for all joints.
bool positionMove(int j, double ref) override
Set new reference point for a single axis.
bool getMotorEncoder(int m, double *v) override
Read the value of an encoder.
bool resetMotorEncoder(int m) override
Reset encoder, single joint.
bool getMaxCurrent(int j, double *v) override
Returns the maximum electric current allowed for a given motor.
bool setEncoder(int j, double val) override
Set the value of the encoder for a given joint.
bool setImpedance(int j, double stiff, double damp) override
Set current impedance gains (stiffness,damping) for a specific joint.
bool getPidErrorLimit(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *limit) override
Get the error limit for the controller on a specific joint.
bool getRefPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
bool abortCalibration() override
bool setRefDutyCycle(int j, double v) override
Sets the reference dutycycle to a single motor.
bool getRefPositions(double *refs) override
Get the last position reference for all axes.
bool getRefTorque(int j, double *t) override
Get the reference value of the torque for a given joint.
bool getDutyCycles(double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool getMotorTorqueParams(int j, yarp::dev::MotorTorqueParameters *params) override
Get a subset of motor parameters (bemf, ktau etc) useful for torque control.
bool setMotorEncoders(const double *vals) override
Set the value of all encoders.
bool getPidError(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *err) override
Get the current error for a joint.
bool getPidReference(const yarp::dev::PidControlTypeEnum &pidtype, int j, double *ref) override
Get the current reference of the pid controller for a specific joint.
bool setPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, const double *refs) override
Set the controller reference, multiple axes.
bool setMaxCurrent(int j, double v) override
Set the maximum electric current going to a given motor.
bool getAmpStatus(int *st) override
Get the status of the amplifiers, coded in a 32 bits integer for each amplifier (at the moment contai...
bool getRefCurrent(int j, double *t) override
Get the reference value of the current for a single motor.
bool setPWMLimit(int m, const double val) override
bool getMotorEncoderAcceleration(int m, double *acc) override
Read the instantaneous acceleration of an axis.
yarp::os::Stamp getLastInputStamp() override
Return the time stamp relative to the last acquisition.
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
bool getTorqueRange(int j, double *min, double *max) override
Get the full scale of the torque sensor of a given joint.
bool calibrateWholePart() override
calibrateWholePart: call the procedure for calibrating the whole device
bool velocityMove(int j, double v) override
Set new reference speed for a single axis.
bool quitCalibrate() override
quitCalibrate: interrupt the calibration procedure
ControlBoardWrapper & operator=(const ControlBoardWrapper &)=delete
bool getRefDutyCycles(double *v) override
Gets the last reference sent using the setRefDutyCycles function.
bool getEncodersTimed(double *encs, double *t) override
Read the instantaneous acceleration of all axes.
bool getDutyCycle(int j, double *v) override
Gets the current dutycycle of the output of the amplifier (i.e.
bool stop() override
Stop motion, multiple joints.
bool resetMotorEncoders() override
Reset encoders.
bool getInteractionMode(int j, yarp::dev::InteractionModeEnum *mode) override
Get the current interaction mode of the robot, values can be stiff or compliant.
bool enablePid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Enable the pid computation for a joint.
bool getTargetPositions(double *refs) override
Get the last position reference for all axes.
bool getEncoderSpeed(int j, double *sp) override
Read the istantaneous speed of an axis.
bool getMotorEncoderSpeed(int m, double *sp) override
Read the istantaneous speed of an axis.
bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override
Sets number of counts per revolution for motor encoder m.
bool getNumberOfMotors(int *num) override
Retrieves the number of controlled axes from the current physical interface.
bool setPeakCurrent(int m, const double val) override
bool setNominalCurrent(int m, const double val) override
bool setPidOffset(const yarp::dev::PidControlTypeEnum &pidtype, int j, double v) override
Set offset value for a given controller.
bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override
gets number of counts per revolution for motor encoder m.
bool setPid(const yarp::dev::PidControlTypeEnum &pidtype, int j, const yarp::dev::Pid &p) override
Set new pid value for a joint axis.
yarp::dev::IRemoteCalibrator * getCalibratorDevice() override
getCalibratorDevice: return the pointer stored with the setCalibratorDevice
bool disableAmp(int j) override
Disable the amplifier on a specific joint.
bool getPidOutputs(const yarp::dev::PidControlTypeEnum &pidtype, double *outs) override
Get the output of the controllers (e.g.
bool parkSingleJoint(int j, bool _wait=true) override
parkSingleJoint(): start the parking procedure for the single joint
bool getImpedanceOffset(int j, double *offset) override
Get current force Offset for a specific joint.
bool setPosition(int j, double ref) override
Set new position for a single axis.
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 getRemoteVariable(std::string key, yarp::os::Bottle &val) override
bool resetPid(const yarp::dev::PidControlTypeEnum &pidtype, int j) override
Reset the controller of a given joint, usually sets the current status of the joint as the reference ...
bool getNumberOfMotorEncoders(int *num) override
Get the number of available motor encoders.
bool getTorque(int j, double *t) override
Get the value of the torque on a given joint (this is the feedback if you have a torque sensor).
bool calibrateSingleJoint(int j) override
calibrateSingleJoint: call the calibration procedure for the single joint
bool setRefSpeeds(const double *spds) override
Set reference speed on all joints.
bool getEncoders(double *encs) override
Read the position of all axes.
bool setLimits(int j, double min, double max) override
Set the software limits for a particular axis, the behavior of the control card when these limits are...
bool calibrationDone(int j) override
Check whether the calibration has been completed.
bool homingSingleJoint(int j) override
homingSingleJoint: call the homing procedure for a single joint
bool getRefAcceleration(int j, double *acc) override
Get reference acceleration for a joint.
bool getEncoder(int j, double *v) override
Read the value of an encoder.
bool setPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, const double *limits) override
Get the error limit for the controller on all joints.
bool checkMotionDone(int j, bool *flag) override
Check if the current trajectory is terminated.
bool setImpedanceOffset(int j, double offset) override
Set current force Offset for a specific joint.
bool getRemoteVariablesList(yarp::os::Bottle *listOfKeys) override
bool setRefAccelerations(const double *accs) override
Set reference acceleration on all joints.
bool homingWholePart() override
homingWholePart: call the homing procedure for a the whole part/device
bool getRefSpeed(int j, double *ref) override
Get reference speed for a joint.
bool getPid(const yarp::dev::PidControlTypeEnum &pidtype, int j, yarp::dev::Pid *p) override
Get current pid value for a specific joint.
bool isCalibratorDevicePresent(bool *isCalib) override
isCalibratorDevicePresent: check if a calibrator device has been set
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 getPidErrors(const yarp::dev::PidControlTypeEnum &pidtype, double *errs) override
Get the error of all joints.
bool setMotorEncoder(int m, const double val) override
Set the value of the encoder for a given joint.
ControlBoardWrapper & operator=(ControlBoardWrapper &&)=delete
bool setInteractionMode(int j, yarp::dev::InteractionModeEnum mode) override
Set the interaction mode of the robot, values can be stiff or compliant.
bool getPWM(int m, double *val) override
bool getTorqueRanges(double *min, double *max) override
Get the full scale of the torque sensors of all joints.
ControlBoardWrapper(const ControlBoardWrapper &)=delete
bool getEncoderAcceleration(int j, double *acc) override
Read the instantaneous acceleration of an axis.
~ControlBoardWrapper() override
bool getRefSpeeds(double *spds) override
Get reference speed of all joints.
bool setPidErrorLimit(const yarp::dev::PidControlTypeEnum &pidtype, int j, double limit) override
Set the error limit for the controller on a specifi joint.
bool close() override
Close the device driver by deallocating all resources and closing ports.
bool getPidErrorLimits(const yarp::dev::PidControlTypeEnum &pidtype, double *limits) override
Get the error limit for all controllers.
bool resetEncoders() override
Reset encoders.
bool isPidEnabled(const yarp::dev::PidControlTypeEnum &pidtype, int j, bool *enabled) override
Get the current status (enabled/disabled) of the pid.
bool setCalibrationParameters(int j, const yarp::dev::CalibrationParameters &params) override
Start calibration, this method is very often platform specific.
bool getRefAccelerations(double *accs) override
Get reference acceleration of all joints.
bool resetEncoder(int j) override
Reset encoder, single joint.
bool getCurrent(int j, double *val) override
Read the electric current going to a given motor.
bool setMotorTorqueParams(int j, const yarp::dev::MotorTorqueParameters params) override
Set a subset of motor parameters (bemf, ktau etc) useful for torque control.
ControlBoardWrapper(ControlBoardWrapper &&)=delete
bool getMotorEncoderTimed(int m, double *v, double *t) override
Read the instantaneous position of a motor encoder.
bool setRefAcceleration(int j, double acc) override
Set reference acceleration for a joint.
bool getCurrentImpedanceLimit(int j, double *min_stiff, double *max_stiff, double *min_damp, double *max_damp) override
Get the current impedandance limits for a specific joint.
bool getEncoderSpeeds(double *spds) override
Read the instantaneous speed of all axes.
bool getJointType(int j, yarp::dev::JointTypeEnum &type) override
bool getPidReferences(const yarp::dev::PidControlTypeEnum &pidtype, double *refs) override
Get the current reference of all pid controllers.
bool setRemoteVariable(std::string key, const yarp::os::Bottle &val) override
bool parkWholePart() override
parkWholePart: start the parking procedure for the whole part
bool getPeakCurrent(int m, double *val) override
bool getGearboxRatio(int m, double *val) override
Get the gearbox ratio for a specific motor.
bool quitPark() override
quitPark: interrupt the park procedure
bool getAxisName(int j, std::string &name) override
bool setVelLimits(int j, double min, double max) override
Set the software velocity limits for a particular axis, the behavior of the control card when these l...
void run() override
The thread main loop deals with writing on ports here.
bool attachAll(const yarp::dev::PolyDriverList &l) override
Attach to a list of objects.
bool getVelLimits(int j, double *min, double *max) override
Get the software velocity limits for a particular axis.
bool getRefTorques(double *refs) override
Get the reference value of the torque for all joints.
bool setPositions(const int n_joints, const int *joints, const double *dpos) override
Set new reference point for all axes.
bool getMotorEncodersTimed(double *encs, double *t) override
Read the instantaneous position of all motor encoders.
void resize(int _deviceNum, int _maxJointsNumForDevice, WrappedDevice *_device)
MultiJointData()=default
SubDevice ** subdevices_p
Helper object for parsing RPC port messages.
Callback implementation after buffered input.
SubDevice * getSubdevice(unsigned int i)
Definition: SubDevice.h:129
Interface implemented by all device drivers.
Definition: DeviceDriver.h:38
Interface for control devices, amplifier commands.
Interface for getting information about specific axes, if available.
Definition: IAxisInfo.h:43
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.
Definition: IControlMode.h:28
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...
Control board, encoder interface.
Control board, encoder interface.
Definition: IMotor.h:99
Interface for an object that can wrap/attach to to another.
Interface for controlling an axis, by sending directly a PWM reference signal to a motor.
Definition: IPWMControl.h:28
Interface for a generic control board device implementing a PID controller, with scaled arguments.
Definition: IPidControl.h:211
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 container for a device driver.
Definition: PolyDriver.h:27
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
The Node class.
Definition: Node.h:27
An abstraction for a periodic thread.
A mini-server for network communication.
Definition: Port.h:50
A class for storing options and configuration information.
Definition: Property.h:37
A base class for nested structures that can be searched.
Definition: Searchable.h:69
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:25
PidControlTypeEnum
Definition: PidEnums.h:21
std::uint32_t NetUint32
Definition of the NetUint32 type.
Definition: NetUint32.h:33
ROSTopicUsageType
Definition: yarpRosHelper.h:19