YARP
Yet Another Robot Platform
ControlBoardWrapperControlMode.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
7 
9 
10 
12 {
13  size_t off;
14  try {
15  off = device.lut.at(j).offset;
16  } catch (...) {
17  yCError(CONTROLBOARD, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
18  return false;
19  }
20  size_t subIndex = device.lut[j].deviceEntry;
21 
22  SubDevice* p = device.getSubdevice(subIndex);
23  if (!p) {
24  return false;
25  }
26 
27  if (p->iMode) {
28  return p->iMode->getControlMode(static_cast<int>(off + p->base), mode);
29  }
30  return false;
31 }
32 
33 
35 {
36  int* all_mode = new int[device.maxNumOfJointsInDevices];
37  bool ret = true;
38  for (size_t d = 0; d < device.subdevices.size(); d++) {
40  if (!p) {
41  ret = false;
42  break;
43  }
44 
45  if ((p->iMode) && (ret = p->iMode->getControlModes(all_mode))) {
46  for (size_t juser = p->wbase, jdevice = p->base; juser <= p->wtop; juser++, jdevice++) {
47  modes[juser] = all_mode[jdevice];
48  }
49  } else {
50  printError("getControlModes", p->id, ret);
51  ret = false;
52  break;
53  }
54  }
55 
56  delete[] all_mode;
57  return ret;
58 }
59 
60 
61 bool ControlBoardWrapperControlMode::getControlModes(const int n_joint, const int* joints, int* modes)
62 {
63  bool ret = true;
64 
65  for (int l = 0; l < n_joint; l++) {
66  int off = device.lut[joints[l]].offset;
67  size_t subIndex = device.lut[joints[l]].deviceEntry;
68 
69  SubDevice* p = device.getSubdevice(subIndex);
70  if (!p) {
71  return false;
72  }
73 
74  if (p->iMode) {
75  ret = ret && p->iMode->getControlMode(static_cast<int>(off + p->base), &modes[l]);
76  } else {
77  ret = false;
78  }
79  }
80  return ret;
81 }
82 
83 
84 bool ControlBoardWrapperControlMode::setControlMode(const int j, const int mode)
85 {
86  bool ret = true;
87  size_t off;
88  try {
89  off = device.lut.at(j).offset;
90  } catch (...) {
91  yCError(CONTROLBOARD, "Joint number %d out of bound [0-%zu] for part %s", j, controlledJoints, partName.c_str());
92  return false;
93  }
94  size_t subIndex = device.lut[j].deviceEntry;
95 
96  SubDevice* p = device.getSubdevice(subIndex);
97  if (!p) {
98  return false;
99  }
100 
101  if (p->iMode) {
102  ret = p->iMode->setControlMode(static_cast<int>(off + p->base), mode);
103  }
104  return ret;
105 }
106 
107 
108 bool ControlBoardWrapperControlMode::setControlModes(const int n_joints, const int* joints, int* modes)
109 {
110  bool ret = true;
111 
112  rpcDataMutex.lock();
113  //Reset subdev_jointsVectorLen vector
114  memset(rpcData.subdev_jointsVectorLen, 0x00, sizeof(int) * rpcData.deviceNum);
115 
116  // Create a map of joints for each subDevice
117  size_t subIndex = 0;
118  for (int j = 0; j < n_joints; j++) {
119  subIndex = device.lut[joints[j]].deviceEntry;
120  rpcData.jointNumbers[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] =
121  static_cast<int>(device.lut[joints[j]].offset + rpcData.subdevices_p[subIndex]->base);
122  rpcData.modes[subIndex][rpcData.subdev_jointsVectorLen[subIndex]] = modes[j];
123  rpcData.subdev_jointsVectorLen[subIndex]++;
124  }
125 
126  for (subIndex = 0; subIndex < rpcData.deviceNum; subIndex++) {
127  if (rpcData.subdevices_p[subIndex]->iMode) {
129  } else {
130  ret = false;
131  }
132  }
133  rpcDataMutex.unlock();
134  return ret;
135 }
136 
137 
139 {
140  bool ret = true;
141  int j_wrap = 0; // index of the wrapper joint
142 
143  int nDev = device.subdevices.size();
144  for (int subDev_idx = 0; subDev_idx < nDev; subDev_idx++) {
145  size_t subIndex = device.lut[j_wrap].deviceEntry;
146  SubDevice* p = device.getSubdevice(subIndex);
147  if (!p) {
148  return false;
149  }
150 
151  int wrapped_joints = static_cast<int>((p->top - p->base) + 1);
152  int* joints = new int[wrapped_joints];
153 
154  if (p->iMode) {
155  // versione comandi su subset di giunti
156  for (int j_dev = 0; j_dev < wrapped_joints; j_dev++) {
157  joints[j_dev] = static_cast<int>(p->base + j_dev); // for all joints is equivalent to add offset term
158  }
159 
160  ret = ret && p->iMode->setControlModes(wrapped_joints, joints, &modes[j_wrap]);
161  j_wrap += wrapped_joints;
162  }
163 
164  if (joints != nullptr) {
165  delete[] joints;
166  joints = nullptr;
167  }
168  }
169 
170  return ret;
171 }
const yarp::os::LogComponent & CONTROLBOARD()
bool ret
void printError(const std::string &func_name, const std::string &info, bool result)
bool getControlModes(int *modes) override
Get the current control mode (multiple joints).
bool setControlMode(const int j, const int mode) override
Set the current control mode.
bool getControlMode(int j, int *mode) override
Get the current control mode.
bool setControlModes(const int n_joints, const int *joints, int *modes) override
Set the current control mode for a subset of axes.
int * subdev_jointsVectorLen
SubDevice ** subdevices_p
size_t base
Definition: SubDevice.h:55
yarp::dev::IControlMode * iMode
Definition: SubDevice.h:78
std::string id
Definition: SubDevice.h:54
size_t top
Definition: SubDevice.h:56
size_t wbase
Definition: SubDevice.h:57
std::vector< DevicesLutEntry > lut
Definition: SubDevice.h:122
SubDevice * getSubdevice(size_t i)
Definition: SubDevice.h:125
size_t maxNumOfJointsInDevices
Definition: SubDevice.h:123
SubDeviceVector subdevices
Definition: SubDevice.h:121
virtual bool setControlMode(const int j, const int mode)=0
Set the current control mode.
virtual bool setControlModes(const int n_joint, const int *joints, int *modes)=0
Set the current control mode for a subset of axes.
virtual bool getControlModes(int *modes)=0
Get the current control mode (multiple joints).
virtual bool getControlMode(int j, int *mode)=0
Get the current control mode.
#define yCError(component,...)
Definition: LogComponent.h:154