YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
ControlBoard_nws_ros.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2023 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
14#include <yarp/rosmsg/impl/yarpRosHelper.h>
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
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 for node_name parameter
77 if (!config.check("node_name")) {
78 yCError(CONTROLBOARD) << nodeName << " cannot find node_name parameter";
79 return false;
80 }
81 nodeName = config.find("node_name").asString();
82 if(nodeName[0] != '/'){
83 yCError(CONTROLBOARD) << "node_name must begin with an initial /";
84 return false;
85 }
86
87 // check for topic_name parameter
88 if (!config.check("topic_name")) {
89 yCError(CONTROLBOARD) << nodeName << " cannot find topic_name parameter";
90 return false;
91 }
92 topicName = config.find("topic_name").asString();
93 if(topicName[0] != '/'){
94 yCError(CONTROLBOARD) << "topic_name must begin with an initial /";
95 return false;
96 }
97 yCInfo(CONTROLBOARD) << "topic_name is " << topicName;
98 // call ROS node/topic initialization
99 node = new yarp::os::Node(nodeName);
100 if (!publisherPort.topic(topicName)) {
101 yCError(CONTROLBOARD) << " opening " << topicName << " Topic, check your configuration";
102 return false;
103 }
104
105 return true;
106}
107
108bool ControlBoard_nws_ros::setDevice(yarp::dev::DeviceDriver* driver)
109{
110 yCAssert(CONTROLBOARD, driver);
111
112 // Save the pointer and subDeviceOwned
113 m_attached_device_ptr = driver;
114
115 m_attached_device_ptr->view(iPositionControl);
116 if (!iPositionControl) {
117 yCError(CONTROLBOARD, "<%s - %s>: IPositionControl interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
118 return false;
119 }
120
121 m_attached_device_ptr->view(iEncodersTimed);
122 if (!iEncodersTimed) {
123 yCError(CONTROLBOARD, "<%s - %s>: IEncodersTimed interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
124 return false;
125 }
126
127 m_attached_device_ptr->view(iTorqueControl);
128 if (!iTorqueControl) {
129 yCWarning(CONTROLBOARD, "<%s - %s>: ITorqueControl interface was not found in attached device.", nodeName.c_str(), topicName.c_str());
130 }
131
132 m_attached_device_ptr->view(iAxisInfo);
133 if (!iAxisInfo) {
134 yCError(CONTROLBOARD, "<%s - %s>: IAxisInfo interface was not found in attached device. Quitting", nodeName.c_str(), topicName.c_str());
135 return false;
136 }
137
138 // Get the number of controlled joints
139 int tmp_axes;
140 if (!iPositionControl->getAxes(&tmp_axes)) {
141 yCError(CONTROLBOARD, "<%s - %s>: Failed to get axes number for attached device ", nodeName.c_str(), topicName.c_str());
142 return false;
143 }
144 if (tmp_axes <= 0) {
145 yCError(CONTROLBOARD, "<%s - %s>: attached device has an invalid number of joints (%d)", nodeName.c_str(), topicName.c_str(), tmp_axes);
146 return false;
147 }
148 subdevice_joints = static_cast<size_t>(tmp_axes);
149 times.resize(subdevice_joints);
150 ros_struct.name.resize(subdevice_joints);
151 ros_struct.position.resize(subdevice_joints);
152 ros_struct.velocity.resize(subdevice_joints);
153 ros_struct.effort.resize(subdevice_joints);
154
155 if (!updateAxisName()) {
156 return false;
157 }
158
159 return true;
160}
161
162
163void ControlBoard_nws_ros::closeDevice()
164{
165 m_attached_device_ptr = nullptr;
166 subdevice_joints = 0;
167
168 times.clear();
169
170 // Clear all interfaces
171 iPositionControl = nullptr;
172 iEncodersTimed = nullptr;
173 iTorqueControl = nullptr;
174 iAxisInfo = nullptr;
175}
176
178{
179 if (!setDevice(poly)) {
180 return false;
181 }
182
183 setPeriod(period);
184 if (!start()) {
185 yCError(CONTROLBOARD) << "Error starting thread";
186 return false;
187 }
188
189 return true;
190}
191
193{
194 // Ensure that the device is not running
195 if (isRunning()) {
196 stop();
197 }
198
199 closeDevice();
200
201 return true;
202}
203
204
205bool ControlBoard_nws_ros::updateAxisName()
206{
207 // IMPORTANT!! This function has to be called BEFORE the thread starts,
208 // the name has to be correct right from the first message!!
209
210 yCAssert(CONTROLBOARD, iAxisInfo);
211
212 std::vector<std::string> tmpVect;
213 for (size_t i = 0; i < subdevice_joints; i++) {
214 std::string tmp;
215 bool ret = iAxisInfo->getAxisName(i, tmp);
216 if (!ret) {
217 yCError(CONTROLBOARD, "Joint name for axis %zu not found!", i);
218 return false;
219 }
220 tmpVect.emplace_back(tmp);
221 }
222
223 yCAssert(CONTROLBOARD, tmpVect.size() == subdevice_joints);
224
225 jointNames = tmpVect;
226
227 return true;
228}
229
230
232{
233 yCAssert(CONTROLBOARD, iEncodersTimed);
234 yCAssert(CONTROLBOARD, iAxisInfo);
235
236 bool positionsOk = iEncodersTimed->getEncodersTimed(ros_struct.position.data(), times.data());
238
239 bool speedsOk = iEncodersTimed->getEncoderSpeeds(ros_struct.velocity.data());
241
242 if (iTorqueControl) {
243 bool torqueOk = iTorqueControl->getTorques(ros_struct.effort.data());
245 }
246
247 // Update the port envelope time by averaging all timestamps
248 time.update(std::accumulate(times.begin(), times.end(), 0.0) / subdevice_joints);
250
251 // Data from HW have been gathered few lines before
253 for (size_t i = 0; i < subdevice_joints; i++) {
254 iAxisInfo->getJointType(i, jType);
256 ros_struct.position[i] = convertDegreesToRadians(ros_struct.position[i]);
257 ros_struct.velocity[i] = convertDegreesToRadians(ros_struct.velocity[i]);
258 }
259 }
260
261 ros_struct.name = jointNames;
262
263 ros_struct.header.seq = counter++;
264 ros_struct.header.stamp = averageTime.getTime();
265
266 publisherPort.write(ros_struct);
267}
const yarp::os::LogComponent & CONTROLBOARD()
constexpr double default_period
bool ret
double convertDegreesToRadians(double degrees)
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.
bool view(T *&x)
Get an interface to the device driver.
virtual bool getAxisName(int axis, std::string &name)=0
virtual bool getJointType(int axis, yarp::dev::JointTypeEnum &type)
Definition IAxisInfo.h:63
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
A mini-server for performing network communication in the background.
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.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
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:31
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
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
void resize(size_t size) override
Resize the vector.
Definition Vector.h:221
iterator begin() noexcept
Returns an iterator to the beginning of the VectorOf.
Definition Vector.h:454
T * data()
Return a pointer to the first element of the vector.
Definition Vector.h:206
iterator end() noexcept
Returns an iterator to the end of the VectorOf.
Definition Vector.h:461
#define yCInfo(component,...)
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
Definition jointData.cpp:13
@ 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