YARP
Yet Another Robot Platform
ControlBoardWrapperCommon.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  *ax = static_cast<int>(controlledJoints);
17  return true;
18 }
19 
20 
22 {
23  size_t off;
24  try {
25  off = device.lut.at(j).offset;
26  } catch (...) {
27  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
28  return false;
29  }
30  size_t subIndex = device.lut[j].deviceEntry;
31 
32  SubDevice* p = device.getSubdevice(subIndex);
33 
34  if (!p) {
35  return false;
36  }
37 
38  if (p->pos) {
39  return p->pos->setRefAcceleration(static_cast<int>(off + p->base), acc);
40  }
41  return false;
42 }
43 
44 
46 {
47  bool ret = true;
48  int j_wrap = 0; // index of the joint from the wrapper side (useful if wrapper joins 2 subdevices)
49 
50  // for all subdevices
51  for (size_t subDev_idx = 0; subDev_idx < device.subdevices.size(); subDev_idx++) {
52  SubDevice* p = device.getSubdevice(subDev_idx);
53 
54  if (!p) {
55  return false;
56  }
57 
58  int wrapped_joints = static_cast<int>((p->top - p->base) + 1);
59  int* joints = new int[wrapped_joints]; // to be defined once and for all?
60 
61  if (p->pos) {
62  // verione comandi su subset di giunti
63  for (int j_dev = 0; j_dev < wrapped_joints; j_dev++) {
64  joints[j_dev] = static_cast<int>(p->base + j_dev);
65  }
66 
67  ret = ret && p->pos->setRefAccelerations(wrapped_joints, joints, &accs[j_wrap]);
68  j_wrap += wrapped_joints;
69  } else {
70  ret = false;
71  }
72 
73  if (joints != nullptr) {
74  delete[] joints;
75  joints = nullptr;
76  }
77  }
78 
79  return ret;
80 }
81 
82 
83 bool ControlBoardWrapperCommon::setRefAccelerations(const int n_joints, const int* joints, const double* accs)
84 {
85  bool ret = true;
86 
87  rpcDataMutex.lock();
88  //Reset subdev_jointsVectorLen vector
89  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
90 
91  // Create a map of joints for each subDevice
92  size_t subIndex = 0;
93  for (int j = 0; j < n_joints; j++) {
94  subIndex = device.lut[joints[j]].deviceEntry;
95  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
96  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
97  rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] = accs[j];
98  rpcData.subdev_jointsVectorLen[subIndex]++;
99  }
100 
101  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
102  if (rpcData.subdevices_p[subIndex]->pos) {
104  } else {
105  ret = false;
106  }
107  }
108  rpcDataMutex.unlock();
109  return ret;
110 }
111 
112 
114 {
115  size_t off;
116  try {
117  off = device.lut.at(j).offset;
118  } catch (...) {
119  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
120  return false;
121  }
122  size_t subIndex = device.lut[j].deviceEntry;
123 
124  SubDevice* p = device.getSubdevice(subIndex);
125 
126  if (!p) {
127  return false;
128  }
129 
130  if (p->pos) {
131  return p->pos->getRefAcceleration(static_cast<int>(off + p->base), acc);
132  }
133  *acc = 0;
134  return false;
135 }
136 
137 
139 {
140  auto* references = new double[device.maxNumOfJointsInDevices];
141  bool ret = true;
142  for (size_t d = 0; d < device.subdevices.size(); d++) {
143  SubDevice* p = device.getSubdevice(d);
144  if (!p) {
145  ret = false;
146  break;
147  }
148 
149  if ((p->pos) && (ret = p->pos->getRefAccelerations(references))) {
150  for (size_t juser = p->wbase, jdevice = p->base; juser <= p->wtop; juser++, jdevice++) {
151  accs[juser] = references[jdevice];
152  }
153  } else {
154  printError("getRefAccelerations", p->id, ret);
155  ret = false;
156  break;
157  }
158  }
159 
160  delete[] references;
161  return ret;
162 }
163 
164 
165 bool ControlBoardWrapperCommon::getRefAccelerations(const int n_joints, const int* joints, double* accs)
166 {
167  bool ret = true;
168 
169  rpcDataMutex.lock();
170  //Reset subdev_jointsVectorLen vector
171  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
172 
173  // Create a map of joints for each subDevice
174  size_t subIndex = 0;
175  for (int j = 0; j < n_joints; j++) {
176  subIndex = device.lut[joints[j]].deviceEntry;
177  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
178  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
179  rpcData.subdev_jointsVectorLen[subIndex]++;
180  }
181 
182  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
183  if (rpcData.subdevices_p[subIndex]->pos) {
185  } else {
186  ret = false;
187  }
188  }
189 
190  if (ret) {
191  // ReMix values by user expectations
192  for (size_t i = 0; i < rpcData.deviceNum; i++) {
193  rpcData.subdev_jointsVectorLen[i] = 0; // reset tmp index
194  }
195 
196  // fill the output vector
197  for (int j = 0; j < n_joints; j++) {
198  subIndex = device.lut[joints[j]].deviceEntry;
199  accs[j] = rpcData.values[subIndex][rpcData.subdev_jointsVectorLen[subIndex]];
200  rpcData.subdev_jointsVectorLen[subIndex]++;
201  }
202  } else {
203  for (int j = 0; j < n_joints; j++) {
204  accs[j] = 0;
205  }
206  }
207  rpcDataMutex.unlock();
208  return ret;
209 }
210 
211 
213 {
214  size_t off;
215  try {
216  off = device.lut.at(j).offset;
217  } catch (...) {
218  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
219  return false;
220  }
221  size_t subIndex = device.lut[j].deviceEntry;
222 
223  SubDevice* p = device.getSubdevice(subIndex);
224 
225  if (!p) {
226  return false;
227  }
228 
229  if (p->pos) {
230  return p->pos->stop(static_cast<int>(off + p->base));
231  }
232  return false;
233 }
234 
235 
237 {
238  bool ret = true;
239 
240  for (size_t l = 0; l < controlledJoints; l++) {
241  size_t off = device.lut[l].offset;
242  size_t subIndex = device.lut[l].deviceEntry;
243 
244  SubDevice* p = device.getSubdevice(subIndex);
245 
246  if (!p) {
247  return false;
248  }
249 
250  if (p->pos) {
251  ret = ret && p->pos->stop(static_cast<int>(off + p->base));
252  } else {
253  ret = false;
254  }
255  }
256  return ret;
257 }
258 
259 
260 bool ControlBoardWrapperCommon::stop(const int n_joints, const int* joints)
261 {
262  bool ret = true;
263 
264  rpcDataMutex.lock();
265  //Reset subdev_jointsVectorLen vector
266  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
267 
268  // Create a map of joints for each subDevice
269  size_t subIndex = 0;
270  for (int j = 0; j < n_joints; j++) {
271  subIndex = device.lut[joints[j]].deviceEntry;
272  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
273  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
274  rpcData.subdev_jointsVectorLen[subIndex]++;
275  }
276 
277  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
278  if (rpcData.subdevices_p[subIndex]->pos) {
279  ret = ret && rpcData.subdevices_p[subIndex]->pos->stop(rpcData.subdev_jointsVectorLen[subIndex], rpcData.jointNumbers[subIndex]);
280  } else {
281  ret = false;
282  }
283  }
284  rpcDataMutex.unlock();
285  return ret;
286 }
287 
288 
290 {
291  *num = static_cast<int>(controlledJoints);
292  return true;
293 }
294 
295 
297 {
298  auto* currs = new double[device.maxNumOfJointsInDevices];
299  bool ret = true;
300  for (size_t d = 0; d < device.subdevices.size(); d++) {
301  ret = false;
302  SubDevice* p = device.getSubdevice(d);
303  if (!p) {
304  break;
305  }
306 
307  if (p->iCurr) {
308  ret = p->iCurr->getCurrents(currs);
309  } else if (p->amp) {
310  ret = p->amp->getCurrents(currs);
311  }
312 
313  if (ret) {
314  for (size_t juser = p->wbase, jdevice = p->base; juser <= p->wtop; juser++, jdevice++) {
315  vals[juser] = currs[jdevice];
316  }
317  } else {
318  printError("getCurrents", p->id, ret);
319  break;
320  }
321  }
322  delete[] currs;
323  return ret;
324 }
325 
326 
328 {
329  size_t off;
330  try {
331  off = device.lut.at(j).offset;
332  } catch (...) {
333  yCError(CONTROLBOARDWRAPPER, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
334  return false;
335  }
336  size_t subIndex = device.lut[j].deviceEntry;
337 
338  SubDevice* p = device.getSubdevice(subIndex);
339  if (!p) {
340  return false;
341  }
342 
343  if (p->iCurr) {
344  return p->iCurr->getCurrent(static_cast<int>(off + p->base), val);
345  }
346 
347  if (p->amp) {
348  return p->amp->getCurrent(static_cast<int>(off + p->base), val);
349  }
350  *val = 0.0;
351  return false;
352 }
ControlBoardWrapperCommon::rpcData
MultiJointData rpcData
Definition: ControlBoardWrapperCommon.h:28
yarp::dev::IPositionControl::setRefAccelerations
virtual bool setRefAccelerations(const double *accs)=0
Set reference acceleration on all joints.
ControlBoardWrapperLogComponent.h
ControlBoardWrapperCommon::stop
bool stop()
Definition: ControlBoardWrapperCommon.cpp:236
MultiJointData::values
double ** values
Definition: MultiJointData.h:23
MultiJointData::jointNumbers
int ** jointNumbers
Definition: MultiJointData.h:21
yarp::dev::IPositionControl::stop
virtual bool stop(int j)=0
Stop motion, single joint.
SubDevice::pos
yarp::dev::IPositionControl * pos
Definition: SubDevice.h:71
ret
bool ret
Definition: ImplementAxisInfo.cpp:72
ControlBoardWrapperCommon::getCurrent
bool getCurrent(int m, double *curr)
Definition: ControlBoardWrapperCommon.cpp:327
yarp::dev::IPositionControl::getRefAcceleration
virtual bool getRefAcceleration(int j, double *acc)=0
Get reference acceleration for a joint.
SubDevice::top
size_t top
Definition: SubDevice.h:59
yarp::dev::IAmplifierControl::getCurrent
virtual bool getCurrent(int j, double *val)=0
MultiJointData::subdev_jointsVectorLen
int * subdev_jointsVectorLen
Definition: MultiJointData.h:20
SubDevice::iCurr
yarp::dev::ICurrentControl * iCurr
Definition: SubDevice.h:88
yarp::dev::ICurrentControl::getCurrents
virtual bool getCurrents(double *currs)=0
Get the instantaneous current measurement for all motors.
yarp::dev::IPositionControl::setRefAcceleration
virtual bool setRefAcceleration(int j, double acc)=0
Set reference acceleration for a joint.
MultiJointData::subdevices_p
SubDevice ** subdevices_p
Definition: MultiJointData.h:24
yarp::dev::ICurrentControl::getCurrent
virtual bool getCurrent(int m, double *curr)=0
Get the instantaneous current measurement for a single motor.
ControlBoardWrapperCommon::getRefAcceleration
bool getRefAcceleration(int j, double *acc)
Definition: ControlBoardWrapperCommon.cpp:113
CONTROLBOARDWRAPPER
const yarp::os::LogComponent & CONTROLBOARDWRAPPER()
Definition: ControlBoardWrapperLogComponent.cpp:11
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
ControlBoardWrapperCommon.h
ControlBoardWrapperCommon::device
WrappedDevice device
Definition: ControlBoardWrapperCommon.h:22
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
ControlBoardWrapperCommon::getCurrents
bool getCurrents(double *currs)
Definition: ControlBoardWrapperCommon.cpp:296
yarp::dev::IAmplifierControl::getCurrents
virtual bool getCurrents(double *vals)=0
SubDevice::base
size_t base
Definition: SubDevice.h:58
WrappedDevice::lut
std::vector< DevicesLutEntry > lut
Definition: SubDevice.h:126
ControlBoardWrapperCommon::getNumberOfMotors
bool getNumberOfMotors(int *num)
Definition: ControlBoardWrapperCommon.cpp:289
MultiJointData::deviceNum
size_t deviceNum
Definition: MultiJointData.h:17
ControlBoardWrapperCommon::setRefAcceleration
bool setRefAcceleration(int j, double acc)
Definition: ControlBoardWrapperCommon.cpp:21
SubDevice::wbase
size_t wbase
Definition: SubDevice.h:60
ControlBoardWrapperCommon::getAxes
bool getAxes(int *ax)
Definition: ControlBoardWrapperCommon.cpp:14
ControlBoardWrapperCommon::setRefAccelerations
bool setRefAccelerations(const double *accs)
Definition: ControlBoardWrapperCommon.cpp:45
SubDevice
Definition: SubDevice.h:55
ControlBoardWrapperCommon::rpcDataMutex
std::mutex rpcDataMutex
Definition: ControlBoardWrapperCommon.h:27
ControlBoardWrapperCommon::getRefAccelerations
bool getRefAccelerations(double *accs)
Definition: ControlBoardWrapperCommon.cpp:138
WrappedDevice::maxNumOfJointsInDevices
size_t maxNumOfJointsInDevices
Definition: SubDevice.h:127
yarp::dev::IPositionControl::getRefAccelerations
virtual bool getRefAccelerations(double *accs)=0
Get reference acceleration of all joints.
SubDevice::amp
yarp::dev::IAmplifierControl * amp
Definition: SubDevice.h:75
ControlBoardWrapperCommon::printError
void printError(const std::string &func_name, const std::string &info, bool result)
Definition: ControlBoardWrapperCommon.h:72