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