YARP
Yet Another Robot Platform
ControlBoardWrapperPositionControl.cpp
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 
10 
12 
13 
15 {
16  size_t off;
17  try {
18  off = device.lut.at(j).offset;
19  } catch (...) {
20  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
21  return false;
22  }
23  size_t subIndex = device.lut[j].deviceEntry;
24 
25  SubDevice* p = device.getSubdevice(subIndex);
26  if (!p) {
27  return false;
28  }
29 
30  if (p->pos) {
31  return p->pos->positionMove(static_cast<int>(off + p->base), ref);
32  }
33 
34  return false;
35 }
36 
37 
39 {
40  bool ret = true;
41  int j_wrap = 0; // index of the wrapper joint
42 
43  int nDev = device.subdevices.size();
44  for (int subDev_idx = 0; subDev_idx < nDev; subDev_idx++) {
45  size_t subIndex = device.lut[j_wrap].deviceEntry;
46  SubDevice* p = device.getSubdevice(subIndex);
47 
48  if (!p) {
49  return false;
50  }
51 
52  int wrapped_joints = static_cast<int>((p->top - p->base) + 1);
53  int* joints = new int[wrapped_joints];
54 
55  if (p->pos) {
56  // versione comandi su subset di giunti
57  for (int j_dev = 0; j_dev < wrapped_joints; j_dev++) {
58  joints[j_dev] = static_cast<int>(p->base + j_dev); // for all joints is equivalent to add offset term
59  }
60 
61  ret = ret && p->pos->positionMove(wrapped_joints, joints, &refs[j_wrap]);
62  j_wrap += wrapped_joints;
63  } else {
64  ret = false;
65  }
66 
67  if (joints != nullptr) {
68  delete[] joints;
69  joints = nullptr;
70  }
71  }
72 
73  return ret;
74 }
75 
76 
77 bool ControlBoardWrapperPositionControl::positionMove(const int n_joints, const int* joints, const double* refs)
78 {
79  bool ret = true;
80 
81  rpcDataMutex.lock();
82  //Reset subdev_jointsVectorLen vector
83  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
84 
85  // Create a map of joints for each subDevice
86  size_t subIndex = 0;
87  for (int j = 0; j < n_joints; j++) {
88  subIndex = device.lut[joints[j]].deviceEntry;
89  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
90  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
91  rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] = refs[j];
92  rpcData.subdev_jointsVectorLen[subIndex]++;
93  }
94 
95  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
96  if (rpcData.subdevices_p[subIndex]->pos) {
97  ret = ret && rpcData.subdevices_p[subIndex]->pos->positionMove(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], rpcData.values[subIndex]);
98  } else {
99  ret = false;
100  }
101  }
102  rpcDataMutex.unlock();
103  return ret;
104 }
105 
106 
108 {
109  size_t off;
110  try {
111  off = device.lut.at(j).offset;
112  } catch (...) {
113  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
114  return false;
115  }
116  size_t subIndex = device.lut[j].deviceEntry;
117 
118  SubDevice* p = device.getSubdevice(subIndex);
119 
120  if (!p) {
121  return false;
122  }
123 
124  if (p->pos) {
125  bool ret = p->pos->getTargetPosition(static_cast<int>(off + p->base), ref);
126  return ret;
127  }
128  *ref = 0;
129  return false;
130 }
131 
132 
134 {
135  auto* targets = new double[device.maxNumOfJointsInDevices];
136  bool ret = true;
137  for (size_t d = 0; d < device.subdevices.size(); d++) {
138  SubDevice* p = device.getSubdevice(d);
139  if (!p) {
140  ret = false;
141  break;
142  }
143 
144  if ((p->pos) && (ret = p->pos->getTargetPositions(targets))) {
145  for (size_t juser = p->wbase, jdevice = p->base; juser <= p->wtop; juser++, jdevice++) {
146  spds[juser] = targets[jdevice];
147  }
148  } else {
149  printError("getTargetPositions", p->id, ret);
150  ret = false;
151  break;
152  }
153  }
154 
155  delete[] targets;
156  return ret;
157 }
158 
159 
160 bool ControlBoardWrapperPositionControl::getTargetPositions(const int n_joints, const int* joints, double* targets)
161 {
162  bool ret = true;
163 
164  rpcDataMutex.lock();
165  //Reset subdev_jointsVectorLen vector
166  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
167 
168  // Create a map of joints for each subDevice
169  size_t subIndex = 0;
170  for (int j = 0; j < n_joints; j++) {
171  subIndex = device.lut[joints[j]].deviceEntry;
172  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
173  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
174  rpcData.subdev_jointsVectorLen[subIndex]++;
175  }
176 
177  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
178  if (rpcData.subdevices_p[subIndex]->pos) {
180  }
181  }
182 
183  if (ret) {
184  // ReMix values by user expectations
185  for (size_t i = 0; i < rpcData.deviceNum; i++) {
186  rpcData.subdev_jointsVectorLen[i] = 0; // reset tmp index
187  }
188 
189  // fill the output vector
190  for (int j = 0; j < n_joints; j++) {
191  subIndex = device.lut[joints[j]].deviceEntry;
192  targets[j] = rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]];
193  rpcData.subdev_jointsVectorLen[subIndex]++;
194  }
195  } else {
196  for (int j = 0; j < n_joints; j++) {
197  targets[j] = 0;
198  }
199  }
200  rpcDataMutex.unlock();
201  return ret;
202 }
203 
204 
206 {
207  size_t off;
208  try {
209  off = device.lut.at(j).offset;
210  } catch (...) {
211  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
212  return false;
213  }
214  size_t subIndex = device.lut[j].deviceEntry;
215 
216  SubDevice* p = device.getSubdevice(subIndex);
217  if (!p) {
218  return false;
219  }
220 
221  if (p->pos) {
222  return p->pos->relativeMove(static_cast<int>(off + p->base), delta);
223  }
224 
225  return false;
226 }
227 
228 
230 {
231  bool ret = true;
232 
233  for (size_t l = 0; l < controlledJoints; l++) {
234  int off = device.lut[l].offset;
235  size_t subIndex = device.lut[l].deviceEntry;
236 
237  SubDevice* p = device.getSubdevice(subIndex);
238  if (!p) {
239  return false;
240  }
241 
242  if (p->pos) {
243  ret = ret && p->pos->relativeMove(static_cast<int>(off + p->base), deltas[l]);
244  } else {
245  ret = false;
246  }
247  }
248  return ret;
249 }
250 
251 
252 bool ControlBoardWrapperPositionControl::relativeMove(const int n_joints, const int* joints, const double* deltas)
253 {
254  bool ret = true;
255 
256  rpcDataMutex.lock();
257  //Reset subdev_jointsVectorLen vector
258  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
259 
260  // Create a map of joints for each subDevice
261  size_t subIndex = 0;
262  for (int j = 0; j < n_joints; j++) {
263  subIndex = device.lut[joints[j]].deviceEntry;
264  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
265  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
266  rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] = deltas[j];
267  rpcData.subdev_jointsVectorLen[subIndex]++;
268  }
269 
270  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
271  if (rpcData.subdevices_p[subIndex]->pos) {
272  ret = ret && rpcData.subdevices_p[subIndex]->pos->relativeMove(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], rpcData.values[subIndex]);
273  } else {
274  ret = false;
275  }
276  }
277  rpcDataMutex.unlock();
278  return ret;
279 }
280 
281 
283 {
284  size_t off;
285  try {
286  off = device.lut.at(j).offset;
287  } catch (...) {
288  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
289  return false;
290  }
291  size_t subIndex = device.lut[j].deviceEntry;
292 
293  SubDevice* p = device.getSubdevice(subIndex);
294 
295  if (!p) {
296  return false;
297  }
298 
299  if (p->pos) {
300  return p->pos->checkMotionDone(static_cast<int>(off + p->base), flag);
301  }
302 
303  return false;
304 }
305 
306 
308 {
309  bool ret = true;
310 
311  rpcDataMutex.lock();
312  //Reset subdev_jointsVectorLen vector
313  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
314 
315  // Create a map of joints for each subDevice
316  // In this case the "all joint version" of checkMotionDone(bool *flag) cannot be
317  // called because the return value is an 'and' of all joints.
318  // Therefore only the corret joints must be evaluated.
319 
320  size_t subIndex = 0;
321  for (size_t j = 0; j < controlledJoints; j++) {
322  subIndex = device.lut[j].deviceEntry;
323  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
324  static_cast<int>(device.lut[j].offset + rpcData.subdevices_p[subIndex]->base);
325  rpcData.subdev_jointsVectorLen[subIndex]++;
326  }
327 
328  bool tmp_subdeviceDone = true;
329  bool tmp_deviceDone = true;
330 
331  // for each subdevice wrapped call checkmotiondone only on interested joints
332  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
333  if (rpcData.subdevices_p[subIndex]->pos) {
334  ret = ret && rpcData.subdevices_p[subIndex]->pos->checkMotionDone(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], &tmp_subdeviceDone);
335  tmp_deviceDone &= tmp_subdeviceDone;
336  }
337  }
338  rpcDataMutex.unlock();
339 
340  // return a single value to the caller
341  *flag = tmp_deviceDone;
342  return ret;
343 }
344 
345 
346 bool ControlBoardWrapperPositionControl::checkMotionDone(const int n_joints, const int* joints, bool* flags)
347 {
348  bool ret = true;
349  bool tmp = true;
350  bool XFlags = true;
351 
352  rpcDataMutex.lock();
353  //Reset subdev_jointsVectorLen vector
354  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
355 
356  // Create a map of joints for each subDevice
357  size_t subIndex = 0;
358  for (int j = 0; j < n_joints; j++) {
359  subIndex = device.lut[joints[j]].deviceEntry;
360  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
361  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
362  rpcData.subdev_jointsVectorLen[subIndex]++;
363  }
364 
365  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
366  if (rpcData.subdevices_p[subIndex]->pos) {
367  ret = ret && rpcData.subdevices_p[subIndex]->pos->checkMotionDone(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], &XFlags);
368  tmp = tmp && XFlags;
369  } else {
370  ret = false;
371  }
372  }
373  if (ret) {
374  *flags = tmp;
375  } else {
376  *flags = false;
377  }
378  rpcDataMutex.unlock();
379  return ret;
380 }
381 
382 
384 {
385  size_t off;
386  try {
387  off = device.lut.at(j).offset;
388  } catch (...) {
389  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
390  return false;
391  }
392  size_t subIndex = device.lut[j].deviceEntry;
393 
394  SubDevice* p = device.getSubdevice(subIndex);
395  if (!p) {
396  return false;
397  }
398 
399  if (p->pos) {
400  return p->pos->setRefSpeed(static_cast<int>(off + p->base), sp);
401  }
402  return false;
403 }
404 
405 
407 {
408  bool ret = true;
409  int j_wrap = 0; // index of the wrapper joint
410 
411  for (size_t subDev_idx = 0; subDev_idx < device.subdevices.size(); subDev_idx++) {
412  SubDevice* p = device.getSubdevice(subDev_idx);
413 
414  if (!p) {
415  return false;
416  }
417 
418  int wrapped_joints = static_cast<int>((p->top - p->base) + 1);
419  int* joints = new int[wrapped_joints];
420 
421  if (p->pos) {
422  // verione comandi su subset di giunti
423  for (int j_dev = 0; j_dev < wrapped_joints; j_dev++) {
424  joints[j_dev] = static_cast<int>(p->base + j_dev);
425  }
426 
427  ret = ret && p->pos->setRefSpeeds(wrapped_joints, joints, &spds[j_wrap]);
428  j_wrap += wrapped_joints;
429  } else {
430  ret = false;
431  }
432 
433  if (joints != nullptr) {
434  delete[] joints;
435  joints = nullptr;
436  }
437  }
438 
439  return ret;
440 }
441 
442 
443 bool ControlBoardWrapperPositionControl::setRefSpeeds(const int n_joints, const int* joints, const double* spds)
444 {
445  bool ret = true;
446 
447  rpcDataMutex.lock();
448  //Reset subdev_jointsVectorLen vector
449  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
450 
451  // Create a map of joints for each subDevice
452  size_t subIndex = 0;
453  for (int j = 0; j < n_joints; j++) {
454  subIndex = device.lut[joints[j]].deviceEntry;
455  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
456  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
457  rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] = spds[j];
458  rpcData.subdev_jointsVectorLen[subIndex]++;
459  }
460 
461  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
462  if (rpcData.subdevices_p[subIndex]->pos) {
463  ret = ret && rpcData.subdevices_p[subIndex]->pos->setRefSpeeds(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], rpcData.values[subIndex]);
464  } else {
465  ret = false;
466  }
467  }
468  rpcDataMutex.unlock();
469  return ret;
470 }
471 
472 
474 {
475  size_t off;
476  try {
477  off = device.lut.at(j).offset;
478  } catch (...) {
479  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
480  return false;
481  }
482  size_t subIndex = device.lut[j].deviceEntry;
483 
484  SubDevice* p = device.getSubdevice(subIndex);
485 
486  if (!p) {
487  return false;
488  }
489 
490  if (p->pos) {
491  return p->pos->getRefSpeed(static_cast<int>(off + p->base), ref);
492  }
493  *ref = 0;
494  return false;
495 }
496 
497 
499 {
500  auto* references = new double[device.maxNumOfJointsInDevices];
501  bool ret = true;
502  for (size_t d = 0; d < device.subdevices.size(); d++) {
503  SubDevice* p = device.getSubdevice(d);
504  if (!p) {
505  ret = false;
506  break;
507  }
508 
509  if ((p->pos) && (ret = p->pos->getRefSpeeds(references))) {
510  for (size_t juser = p->wbase, jdevice = p->base; juser <= p->wtop; juser++, jdevice++) {
511  spds[juser] = references[jdevice];
512  }
513  } else {
514  printError("getRefSpeeds", p->id, ret);
515  ret = false;
516  break;
517  }
518  }
519 
520  delete[] references;
521  return ret;
522 }
523 
524 
525 bool ControlBoardWrapperPositionControl::getRefSpeeds(const int n_joints, const int* joints, double* spds)
526 {
527  bool ret = true;
528 
529  rpcDataMutex.lock();
530  //Reset subdev_jointsVectorLen vector
531  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
532 
533  // Create a map of joints for each subDevice
534  size_t subIndex = 0;
535  for (int j = 0; j < n_joints; j++) {
536  subIndex = device.lut[joints[j]].deviceEntry;
537  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
538  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
539  rpcData.subdev_jointsVectorLen[subIndex]++;
540  }
541 
542  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
543  if (rpcData.subdevices_p[subIndex]->pos) {
544  ret = ret && rpcData.subdevices_p[subIndex]->pos->getRefSpeeds(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex], rpcData.values[subIndex]);
545  } else {
546  ret = false;
547  }
548  }
549 
550  if (ret) {
551  // ReMix values by user expectations
552  for (size_t i = 0; i < rpcData.deviceNum; i++) {
553  rpcData.subdev_jointsVectorLen[i] = 0; // reset tmp index
554  }
555 
556  // fill the output vector
557  for (int j = 0; j < n_joints; j++) {
558  subIndex = device.lut[joints[j]].deviceEntry;
559  spds[j] = rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]];
560  rpcData.subdev_jointsVectorLen[subIndex]++;
561  }
562  } else {
563  for (int j = 0; j < n_joints; j++) {
564  spds[j] = 0;
565  }
566  }
567  rpcDataMutex.unlock();
568  return ret;
569 }
ControlBoardWrapperCommon::rpcData
MultiJointData rpcData
Definition: ControlBoardWrapperCommon.h:28
ControlBoardWrapperLogComponent.h
yarp::dev::IPositionControl::positionMove
virtual bool positionMove(int j, double ref)=0
Set new reference point for a single axis.
MultiJointData::values
double ** values
Definition: MultiJointData.h:23
MultiJointData::jointNumbers
int ** jointNumbers
Definition: MultiJointData.h:21
SubDevice::pos
yarp::dev::IPositionControl * pos
Definition: SubDevice.h:71
ControlBoardWrapperPositionControl::getTargetPosition
bool getTargetPosition(const int joint, double *ref) override
Get the last position reference for the specified axis.
Definition: ControlBoardWrapperPositionControl.cpp:107
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
ControlBoardWrapperPositionControl::positionMove
bool positionMove(int j, double ref) override
Set new reference point for a single axis.
Definition: ControlBoardWrapperPositionControl.cpp:14
SubDevice::top
size_t top
Definition: SubDevice.h:59
MultiJointData::subdev_jointsVectorLen
int * subdev_jointsVectorLen
Definition: MultiJointData.h:20
yarp::dev::IPositionControl::setRefSpeed
virtual bool setRefSpeed(int j, double sp)=0
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
yarp::dev::IPositionControl::getRefSpeeds
virtual bool getRefSpeeds(double *spds)=0
Get reference speed of all joints.
ControlBoardWrapperPositionControl::setRefSpeed
bool setRefSpeed(int j, double sp) override
Set reference speed for a joint, this is the speed used during the interpolation of the trajectory.
Definition: ControlBoardWrapperPositionControl.cpp:383
ControlBoardWrapperPositionControl.h
MultiJointData::subdevices_p
SubDevice ** subdevices_p
Definition: MultiJointData.h:24
CONTROLBOARDWRAPPER
const yarp::os::LogComponent & CONTROLBOARDWRAPPER()
Definition: ControlBoardWrapperLogComponent.cpp:11
ControlBoardWrapperPositionControl::getTargetPositions
bool getTargetPositions(double *refs) override
Get the last position reference for all axes.
Definition: ControlBoardWrapperPositionControl.cpp:133
yarp::dev::IPositionControl::getRefSpeed
virtual bool getRefSpeed(int j, double *ref)=0
Get reference speed for a joint.
yarp::dev::IPositionControl::checkMotionDone
virtual bool checkMotionDone(int j, bool *flag)=0
Check if the current trajectory is terminated.
ControlBoardWrapperCommon::partName
std::string partName
Definition: ControlBoardWrapperCommon.h:24
ControlBoardWrapperCommon::controlledJoints
size_t controlledJoints
Definition: ControlBoardWrapperCommon.h:23
SubDevice::id
std::string id
Definition: SubDevice.h:57
WrappedDevice::getSubdevice
SubDevice * getSubdevice(size_t i)
Definition: SubDevice.h:129
WrappedDevice::subdevices
SubDeviceVector subdevices
Definition: SubDevice.h:125
ControlBoardWrapperPositionControl::getRefSpeed
bool getRefSpeed(int j, double *ref) override
Get reference speed for a joint.
Definition: ControlBoardWrapperPositionControl.cpp:473
yarp::dev::IPositionControl::relativeMove
virtual bool relativeMove(int j, double delta)=0
Set relative position.
yarp::dev::IPositionControl::getTargetPositions
virtual bool getTargetPositions(double *refs)
Get the last position reference for all axes.
Definition: IPositionControl.h:463
ControlBoardWrapperCommon::device
WrappedDevice device
Definition: ControlBoardWrapperCommon.h:22
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
SubDevice::base
size_t base
Definition: SubDevice.h:58
WrappedDevice::lut
std::vector< DevicesLutEntry > lut
Definition: SubDevice.h:126
yarp::dev::IPositionControl::setRefSpeeds
virtual bool setRefSpeeds(const double *spds)=0
Set reference speed on all joints.
ControlBoardWrapperPositionControl::getRefSpeeds
bool getRefSpeeds(double *spds) override
Get reference speed of all joints.
Definition: ControlBoardWrapperPositionControl.cpp:498
MultiJointData::deviceNum
size_t deviceNum
Definition: MultiJointData.h:17
ControlBoardWrapperPositionControl::setRefSpeeds
bool setRefSpeeds(const double *spds) override
Set reference speed on all joints.
Definition: ControlBoardWrapperPositionControl.cpp:406
yarp::dev::IPositionControl::getTargetPosition
virtual bool getTargetPosition(const int joint, double *ref)
Get the last position reference for the specified axis.
Definition: IPositionControl.h:452
SubDevice::wbase
size_t wbase
Definition: SubDevice.h:60
ControlBoardWrapperPositionControl::relativeMove
bool relativeMove(int j, double delta) override
Set relative position.
Definition: ControlBoardWrapperPositionControl.cpp:205
SubDevice
Definition: SubDevice.h:55
ControlBoardWrapperCommon::rpcDataMutex
std::mutex rpcDataMutex
Definition: ControlBoardWrapperCommon.h:27
WrappedDevice::maxNumOfJointsInDevices
size_t maxNumOfJointsInDevices
Definition: SubDevice.h:127
ControlBoardWrapperPositionControl::checkMotionDone
bool checkMotionDone(int j, bool *flag) override
Check if the current trajectory is terminated.
Definition: ControlBoardWrapperPositionControl.cpp:282
ControlBoardWrapperCommon::printError
void printError(const std::string &func_name, const std::string &info, bool result)
Definition: ControlBoardWrapperCommon.h:72