YARP
Yet Another Robot Platform
ControlBoard_nws_ros.cpp
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 #include "ControlBoard_nws_ros.h"
8 
9 #include <yarp/os/LogComponent.h>
10 #include <yarp/os/LogStream.h>
11 
13 
15 
17 
18 #include <numeric>
19 
20 using namespace yarp::os;
21 using namespace yarp::dev;
22 using namespace yarp::sig;
23 
25  yarp::os::PeriodicThread(default_period)
26 {
27 }
28 
29 
30 void ControlBoard_nws_ros::closePorts()
31 {
32  publisherPort.interrupt();
33  publisherPort.close();
34 
35  delete node;
36  node = nullptr;
37 }
38 
40 {
41  // Ensure that the device is not running
42  if (isRunning()) {
43  stop();
44  }
45 
46  closeDevice();
47  closePorts();
48 
49  return true;
50 }
51 
52 
54 {
55  Property prop;
56  prop.fromString(config.toString());
57 
58  // Check parameter, so if both are present we use the correct one
59  if (prop.check("period")) {
60  if (!prop.find("period").isFloat64()) {
61  yCError(CONTROLBOARD) << "'period' parameter is not a double value";
62  return false;
63  }
64  period = prop.find("period").asFloat64();
65  if (period <= 0) {
66  yCError(CONTROLBOARD) << "'period' parameter is not valid, read value is" << period;
67  return false;
68  }
69  } else {
70  yCDebug(CONTROLBOARD) << "'period' parameter missing, using default thread period = 0.02s";
71  period = default_period;
72  }
73 
74  // Check if we need to create subdevice or if they are
75  // passed later on thorugh attachAll()
76  if (prop.check("subdevice")) {
77  prop.setMonitor(config.getMonitor());
78  if (!openAndAttachSubDevice(prop)) {
79  yCError(CONTROLBOARD, "Error while opening subdevice");
80  return false;
81  }
82  subdevice_ready = true;
83  }
84 
85  // check for node_name parameter
86  if (!config.check("node_name")) {
87  yCError(CONTROLBOARD) << nodeName << " cannot find node_name parameter";
88  return false;
89  }
90  nodeName = config.find("node_name").asString();
91  if(nodeName[0] != '/'){
92  yCError(CONTROLBOARD) << "node_name must begin with an initial /";
93  return false;
94  }
95 
96  // check for topic_name parameter
97  if (!config.check("topic_name")) {
98  yCError(CONTROLBOARD) << nodeName << " cannot find topic_name parameter";
99  return false;
100  }
101  topicName = config.find("topic_name").asString();
102  if(topicName[0] != '/'){
103  yCError(CONTROLBOARD) << "topic_name must begin with an initial /";
104  return false;
105  }
106  yCInfo(CONTROLBOARD) << "topic_name is " << topicName;
107  // call ROS node/topic initialization
108  node = new yarp::os::Node(nodeName);
109  if (!publisherPort.topic(topicName)) {
110  yCError(CONTROLBOARD) << " opening " << topicName << " Topic, check your configuration";
111  return false;
112  }
113 
114  // In case attach is not deferred and the controlboard already owns a valid device
115  // we can start the thread. Otherwise this will happen when attachAll is called
116  if (subdevice_ready) {
117  setPeriod(period);
118  if (!start()) {
119  yCError(CONTROLBOARD) << "Error starting thread";
120  return false;
121  }
122  }
123 
124  return true;
125 }
126 
127 
128 
129 // For the simulator, if a subdevice parameter is given to the wrapper, it will
130 // open it and attach to immediately.
131 bool ControlBoard_nws_ros::openAndAttachSubDevice(Property& prop)
132 {
133  Property p;
134  auto* subDeviceOwned = new PolyDriver;
135  p.fromString(prop.toString());
136 
137  std::string subdevice = prop.find("subdevice").asString();
138  p.setMonitor(prop.getMonitor(), subdevice.c_str()); // pass on any monitoring
139  p.unput("device");
140  p.put("device", subdevice); // subdevice was already checked before
141 
142  // if errors occurred during open, quit here.
143  yCDebug(CONTROLBOARD, "opening subdevice");
144  subDeviceOwned->open(p);
145 
146  if (!subDeviceOwned->isValid()) {
147  yCError(CONTROLBOARD, "opening subdevice... FAILED");
148  return false;
149  }
150 
151  return setDevice(subDeviceOwned, true);
152 }
153 
154 
155 bool ControlBoard_nws_ros::setDevice(yarp::dev::DeviceDriver* driver, bool owned)
156 {
157  yCAssert(CONTROLBOARD, driver);
158 
159  // Save the pointer and subDeviceOwned
160  subdevice_ptr = driver;
161  subdevice_owned = owned;
162 
163  subdevice_ptr->view(iPositionControl);
164  if (!iPositionControl) {
165  yCError(CONTROLBOARD, "<%s - %s>: IPositionControl interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str());
166  return false;
167  }
168 
169  subdevice_ptr->view(iEncodersTimed);
170  if (!iEncodersTimed) {
171  yCError(CONTROLBOARD, "<%s - %s>: IEncodersTimed interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str());
172  return false;
173  }
174 
175  subdevice_ptr->view(iTorqueControl);
176  if (!iTorqueControl) {
177  yCWarning(CONTROLBOARD, "<%s - %s>: ITorqueControl interface was not found in subdevice.", nodeName.c_str(), topicName.c_str());
178  }
179 
180  subdevice_ptr->view(iAxisInfo);
181  if (!iAxisInfo) {
182  yCError(CONTROLBOARD, "<%s - %s>: IAxisInfo interface was not found in subdevice. Quitting", nodeName.c_str(), topicName.c_str());
183  return false;
184  }
185 
186  // Get the number of controlled joints
187  int tmp_axes;
188  if (!iPositionControl->getAxes(&tmp_axes)) {
189  yCError(CONTROLBOARD, "<%s - %s>: Failed to get axes number for subdevice ", nodeName.c_str(), topicName.c_str());
190  return false;
191  }
192  if (tmp_axes <= 0) {
193  yCError(CONTROLBOARD, "<%s - %s>: attached device has an invalid number of joints (%d)", nodeName.c_str(), topicName.c_str(), tmp_axes);
194  return false;
195  }
196  subdevice_joints = static_cast<size_t>(tmp_axes);
197  times.resize(subdevice_joints);
198  ros_struct.name.resize(subdevice_joints);
199  ros_struct.position.resize(subdevice_joints);
200  ros_struct.velocity.resize(subdevice_joints);
201  ros_struct.effort.resize(subdevice_joints);
202 
203  if (!updateAxisName()) {
204  return false;
205  }
206 
207  return true;
208 }
209 
210 
211 void ControlBoard_nws_ros::closeDevice()
212 {
213  // If the subdevice is owned, close and delete the device
214  if (subdevice_owned) {
215  yCAssert(CONTROLBOARD, subdevice_ptr);
216  subdevice_ptr->close();
217  delete subdevice_ptr;
218  }
219  subdevice_ptr = nullptr;
220  subdevice_owned = false;
221  subdevice_joints = 0;
222  subdevice_ready = false;
223 
224  times.clear();
225 
226  // Clear all interfaces
227  iPositionControl = nullptr;
228  iEncodersTimed = nullptr;
229  iTorqueControl = nullptr;
230  iAxisInfo = nullptr;
231 }
232 
234 {
235  // Check if we already instantiated a subdevice previously
236  if (subdevice_ready) {
237  return false;
238  }
239 
240  if (!setDevice(poly, false)) {
241  return false;
242  }
243 
244  setPeriod(period);
245  if (!start()) {
246  yCError(CONTROLBOARD) << "Error starting thread";
247  return false;
248  }
249 
250  return true;
251 }
252 
254 {
255  //check if we already instantiated a subdevice previously
256  if (subdevice_owned) {
257  return false;
258  }
259 
260  // Ensure that the device is not running
261  if (isRunning()) {
262  stop();
263  }
264 
265  closeDevice();
266 
267  return true;
268 }
269 
270 
271 bool ControlBoard_nws_ros::updateAxisName()
272 {
273  // IMPORTANT!! This function has to be called BEFORE the thread starts,
274  // the name has to be correct right from the first message!!
275 
276  yCAssert(CONTROLBOARD, iAxisInfo);
277 
278  std::vector<std::string> tmpVect;
279  for (size_t i = 0; i < subdevice_joints; i++) {
280  std::string tmp;
281  bool ret = iAxisInfo->getAxisName(i, tmp);
282  if (!ret) {
283  yCError(CONTROLBOARD, "Joint name for axis %zu not found!", i);
284  return false;
285  }
286  tmpVect.emplace_back(tmp);
287  }
288 
289  yCAssert(CONTROLBOARD, tmpVect.size() == subdevice_joints);
290 
291  jointNames = tmpVect;
292 
293  return true;
294 }
295 
296 
298 {
299  yCAssert(CONTROLBOARD, iEncodersTimed);
300  yCAssert(CONTROLBOARD, iAxisInfo);
301 
302  bool positionsOk = iEncodersTimed->getEncodersTimed(ros_struct.position.data(), times.data());
303  YARP_UNUSED(positionsOk);
304 
305  bool speedsOk = iEncodersTimed->getEncoderSpeeds(ros_struct.velocity.data());
306  YARP_UNUSED(speedsOk);
307 
308  if (iTorqueControl) {
309  bool torqueOk = iTorqueControl->getTorques(ros_struct.effort.data());
310  YARP_UNUSED(torqueOk);
311  }
312 
313  // Update the port envelope time by averaging all timestamps
314  time.update(std::accumulate(times.begin(), times.end(), 0.0) / subdevice_joints);
315  yarp::os::Stamp averageTime = time;
316 
317  // Data from HW have been gathered few lines before
318  JointTypeEnum jType;
319  for (size_t i = 0; i < subdevice_joints; i++) {
320  iAxisInfo->getJointType(i, jType);
321  if (jType == VOCAB_JOINTTYPE_REVOLUTE) {
322  ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]);
323  ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]);
324  }
325  }
326 
327  ros_struct.name = jointNames;
328 
329  ros_struct.header.seq = counter++;
330  ros_struct.header.stamp = averageTime.getTime();
331 
332  publisherPort.write(ros_struct);
333 }
const yarp::os::LogComponent & CONTROLBOARD()
bool ret
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
void run() override
Loop function.
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
bool detach() override
Detach the object (you must have first called attach).
Interface implemented by all device drivers.
Definition: DeviceDriver.h:35
bool view(T *&x)
Get an interface to the device driver.
Definition: DeviceDriver.h:74
bool close() override
Close the DeviceDriver.
Definition: DeviceDriver.h:61
virtual bool getAxisName(int axis, std::string &name)=0
virtual bool getJointType(int axis, yarp::dev::JointTypeEnum &type)
Definition: IAxisInfo.h:59
virtual bool getEncodersTimed(double *encs, double *time)=0
Read the instantaneous acceleration of all axes.
virtual bool getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all axes.
virtual bool getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool getTorques(double *t)=0
Get the value of the torque for all joints (this is the feedback if you have torque sensors).
A container for a device driver.
Definition: PolyDriver.h:24
The Node class.
Definition: Node.h:24
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
A class for storing options and configuration information.
Definition: Property.h:34
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Property.cpp:1051
std::string toString() const override
Return a standard text representation of the content of the object.
Definition: Property.cpp:1069
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1063
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:1015
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Property.cpp:1041
void unput(const std::string &key)
Remove the association from the given key to a value, if present.
Definition: Property.cpp:1046
void close() override
Stop port activity.
Definition: Publisher.h:85
bool topic(const std::string &name)
Set topic to publish to.
Definition: Publisher.h:64
void interrupt() override
Interrupt any current reads or writes attached to the port.
Definition: Publisher.h:91
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:149
A base class for nested structures that can be searched.
Definition: Searchable.h:66
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
An abstraction for a time stamp and/or sequence number.
Definition: Stamp.h:22
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
Definition: Stamp.cpp:124
double getTime() const
Get the time stamp.
Definition: Stamp.cpp:34
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual bool isFloat64() const
Checks if value is a 64-bit floating point number.
Definition: Value.cpp:150
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
std::vector< std::string > name
Definition: JointState.h:56
std::vector< yarp::conf::float64_t > position
Definition: JointState.h:57
std::vector< yarp::conf::float64_t > velocity
Definition: JointState.h:58
std::vector< yarp::conf::float64_t > effort
Definition: JointState.h:59
yarp::rosmsg::std_msgs::Header header
Definition: JointState.h:55
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
void resize(size_t size) override
Resize the vector.
Definition: Vector.h:222
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
Definition: Vector.h:455
T * data()
Return a pointer to the first element of the vector.
Definition: Vector.h:207
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
Definition: Vector.h:462
#define yCInfo(component,...)
Definition: LogComponent.h:132
#define yCError(component,...)
Definition: LogComponent.h:154
#define yCAssert(component, x)
Definition: LogComponent.h:169
#define yCWarning(component,...)
Definition: LogComponent.h:143
#define yCDebug(component,...)
Definition: LogComponent.h:109
An interface for the device drivers.
@ VOCAB_JOINTTYPE_REVOLUTE
Definition: IAxisInfo.h:27
An interface to the operating system, including Port based communication.
Signal processing.
Definition: Image.h:22
The main, catch-all namespace for YARP.
Definition: dirs.h:16
#define YARP_UNUSED(var)
Definition: api.h:162
double convertDegreesToRadians(double degrees)
convert degrees to radiants for ROS messages
Definition: yarpRosHelper.h:27