YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
ControlBoard_nws_ros2.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef _USE_MATH_DEFINES
7#define _USE_MATH_DEFINES
8#endif
9
11
12#include <chrono>
13#include <functional>
14#include <memory>
15#include <string>
16#include <cmath>
17
19#include <yarp/os/LogStream.h>
20#include <Ros2Utils.h>
21#include <rcutils/logging_macros.h>
22
23using namespace std::chrono_literals;
24using namespace yarp::os;
25using namespace yarp::dev;
26using namespace yarp::sig;
27
28namespace {
29YARP_LOG_COMPONENT(CONTROLBOARD_ROS2, "yarp.ros2.controlBoard_nws_ros2", yarp::os::Log::TraceType);
30
31
33inline double convertDegreesToRadians(double degrees)
34{
35 return degrees / 180.0 * M_PI;
36}
37
38}
39
40
45
46void ControlBoard_nws_ros2::closePorts()
47{
48 // FIXME
49 yCWarning(CONTROLBOARD_ROS2, "FIXME: closePorts() is not implemented yet!");
50 YARP_UNUSED(this);
51}
52
54{
55 if(m_spinner){
56 if(m_spinner->isRunning()){
57 m_spinner->stop();
58 }
59 }
60 // Ensure that the device is not running
61 if (isRunning()) {
62 stop();
63 }
64
65 closeDevice();
66 closePorts();
67
68 return true;
69}
70
71
73{
74 parseParams(config);
76 m_publisher = m_node->create_publisher<sensor_msgs::msg::JointState>(m_topic_name, 10);
77
78 return true;
79}
80
81
82bool ControlBoard_nws_ros2::initRos2Control(const std::string& name){
83
84 m_posTopicName = name+"/position";
85 m_posDirTopicName = name+"/position_direct";
86 m_velTopicName = name+"/velocity";
87 m_getModesSrvName = name+"/get_modes";
88 m_setModesSrvName = name+"/set_modes";
89 m_getVelocitySrvName = name+"/get_velocity";
90 m_getPositionSrvName = name+"/get_position";
91 m_getAvailableModesSrvName = name+"/get_available_modes";
92 m_getJointsNamesSrvName = name+"/get_joints_names";
93
94 // Creating topics ------------------------------------------------------------------------------------------------- //
95
96 if(m_iPositionControl){
97 m_posSubscription = m_node->create_subscription<yarp_control_msgs::msg::Position>(m_posTopicName, 10,
98 std::bind(&ControlBoard_nws_ros2::positionTopic_callback,
99 this, std::placeholders::_1));
100 if(!m_posSubscription){
101 yCError(CONTROLBOARD_ROS2) << "Could not initialize the Position msg subscription";
102 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the Position msg subscription");
103
104 return false;
105 }
106 }
107 if(m_iPositionDirect){
108 m_posDirectSubscription = m_node->create_subscription<yarp_control_msgs::msg::PositionDirect>(m_posDirTopicName, 10,
109 std::bind(&ControlBoard_nws_ros2::positionDirectTopic_callback,
110 this, std::placeholders::_1));
111 if(!m_posDirectSubscription){
112 yCError(CONTROLBOARD_ROS2) << "Could not initialize the Position direct msg subscription";
113 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the Position direct msg subscription");
114
115 return false;
116 }
117 }
118 if(m_iVelocityControl){
119 m_velSubscription = m_node->create_subscription<yarp_control_msgs::msg::Velocity>(m_velTopicName, 10,
120 std::bind(&ControlBoard_nws_ros2::velocityTopic_callback,
121 this, std::placeholders::_1));
122 if(!m_velSubscription){
123 yCError(CONTROLBOARD_ROS2) << "Could not initialize the Velocity msg subscription";
124 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the Velocity msg subscription");
125
126 return false;
127 }
128 }
129
130 // Creating services ----------------------------------------------------------------------------------------------- //
131
132 if(!m_iControlMode){
133 return true;
134 }
135
138 qos.depth=10;
139 rmw_time_t time;
140 time.sec=10000;
141 time.nsec = 0;
142 qos.deadline= time;
143 qos.lifespan=time;
144 qos.liveliness_lease_duration=time;
148 qos.avoid_ros_namespace_conventions = true;
149 m_getControlModesSrv = m_node->create_service<yarp_control_msgs::srv::GetControlModes>(m_getModesSrvName,
150 std::bind(&ControlBoard_nws_ros2::getControlModesCallback,
151 this,std::placeholders::_1,std::placeholders::_2,
152 std::placeholders::_3));
153 if(!m_getControlModesSrv){
154 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetControlModes service";
155 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetControlModes service");
156
157 return false;
158 }
159 m_getPositionSrv = m_node->create_service<yarp_control_msgs::srv::GetPosition>(m_getPositionSrvName,
160 std::bind(&ControlBoard_nws_ros2::getPositionCallback,
161 this,std::placeholders::_1,std::placeholders::_2,
162 std::placeholders::_3));
163 if(!m_getPositionSrv){
164 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetPosition service";
165 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetPosition service");
166
167 return false;
168 }
169 m_getVelocitySrv = m_node->create_service<yarp_control_msgs::srv::GetVelocity>(m_getVelocitySrvName,
170 std::bind(&ControlBoard_nws_ros2::getVelocityCallback,
171 this,std::placeholders::_1,std::placeholders::_2,
172 std::placeholders::_3));
173 if(!m_getVelocitySrv){
174 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetVelocity service";
175 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetVelocity service");
176
177 return false;
178 }
179 m_setControlModesSrv = m_node->create_service<yarp_control_msgs::srv::SetControlModes>(m_setModesSrvName,
180 std::bind(&ControlBoard_nws_ros2::setControlModesCallback,
181 this,std::placeholders::_1,std::placeholders::_2,
182 std::placeholders::_3));
183 if(!m_setControlModesSrv){
184 yCError(CONTROLBOARD_ROS2) << "Could not initialize the SetControlModes service";
185 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the SetControlModes service");
186
187 return false;
188 }
189 m_getAvailableModesSrv = m_node->create_service<yarp_control_msgs::srv::GetAvailableControlModes>(m_getAvailableModesSrvName,
190 std::bind(&ControlBoard_nws_ros2::getAvailableModesCallback,
191 this,std::placeholders::_1,std::placeholders::_2,
192 std::placeholders::_3));
193 if(!m_getAvailableModesSrv){
194 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetAvailableModes service";
195 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetAvailableModes service");
196
197 return false;
198 }
199 m_getJointsNamesSrv = m_node->create_service<yarp_control_msgs::srv::GetJointsNames>(m_getJointsNamesSrvName,
200 std::bind(&ControlBoard_nws_ros2::getJointsNamesCallback,
201 this,std::placeholders::_1,std::placeholders::_2,
202 std::placeholders::_3));
203 if(!m_getJointsNamesSrv){
204 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetJointsNames service";
205 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetJointsNames service");
206
207 return false;
208 }
209
210 m_spinner = new Ros2Spinner(m_node);
211 if (!m_spinner){
212 yCError(CONTROLBOARD_ROS2) << "Could not initialize the GetJointsNames service";
213 RCLCPP_ERROR(m_node->get_logger(),"Could not initialize the GetJointsNames service");
214
215 return false;
216 }
217
218 std::string tmpName;
219 for(size_t i=0; i<m_subdevice_joints; i++){
220 if(!m_iAxisInfo->getAxisName(i,tmpName)){
221 yCError(CONTROLBOARD_ROS2) << "Error retrieving axis" << i << "name. For this device to work, every joint needs a name";
222
223 return false;
224 }
225 m_quickJointRef[tmpName] = i;
226 }
227
228 return true;
229}
230
231
232bool ControlBoard_nws_ros2::setDevice(yarp::dev::DeviceDriver* driver)
233{
235
236 // Save the pointer and subDeviceOwned
237 m_subdevice_ptr = driver;
238
239 m_subdevice_ptr->view(m_iPositionControl);
240 if (!m_iPositionControl) {
241 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IPositionControl interface was not found in attached device.", m_node_name.c_str(), m_topic_name.c_str());
242 }
243
244 m_subdevice_ptr->view(m_iPositionDirect);
245 if (!m_iPositionDirect) {
246 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IPositionDirect interface was not found in attached device.", m_node_name.c_str(), m_posTopicName.c_str());
247 }
248
249 m_subdevice_ptr->view(m_iVelocityControl);
250 if (!m_iVelocityControl) {
251 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IVelocityControl interface was not found in attached device.", m_node_name.c_str(), m_posTopicName.c_str());
252 }
253
254 m_subdevice_ptr->view(m_iControlMode);
255 if (!m_iControlMode) {
256 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IControlMode interface was not found in attached device.", m_node_name.c_str(), m_posTopicName.c_str());
257 }
258
259 m_subdevice_ptr->view(m_iEncodersTimed);
260 if (!m_iEncodersTimed) {
261 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IEncodersTimed interface was not found in attached device. Quitting", m_node_name.c_str(), m_topic_name.c_str());
262 return false;
263 }
264
265 m_subdevice_ptr->view(m_iTorqueControl);
266 if (!m_iTorqueControl) {
267 yCWarning(CONTROLBOARD_ROS2, "<%s - %s>: ITorqueControl interface was not found in attached device.", m_node_name.c_str(), m_topic_name.c_str());
268 }
269
270 m_subdevice_ptr->view(m_iAxisInfo);
271 if (!m_iAxisInfo) {
272 yCError(CONTROLBOARD_ROS2, "<%s - %s>: IAxisInfo interface was not found in attached device. Quitting", m_node_name.c_str(), m_topic_name.c_str());
273 return false;
274 }
275
276 // Get the number of controlled joints
277 int tmp_axes;
278 if (!m_iEncodersTimed->getAxes(&tmp_axes)) {
279 yCError(CONTROLBOARD_ROS2, "<%s - %s>: Failed to get axes number for attached device ", m_node_name.c_str(), m_topic_name.c_str());
280 return false;
281 }
282 if (tmp_axes <= 0) {
283 yCError(CONTROLBOARD_ROS2, "<%s - %s>: attached device has an invalid number of joints (%d)", m_node_name.c_str(), m_topic_name.c_str(), tmp_axes);
284 return false;
285 }
286 m_subdevice_joints = static_cast<size_t>(tmp_axes);
287 m_times.resize(m_subdevice_joints);
288 m_ros_struct.name.resize(m_subdevice_joints);
289 m_ros_struct.position.resize(m_subdevice_joints);
290 m_ros_struct.velocity.resize(m_subdevice_joints);
291 m_ros_struct.effort.resize(m_subdevice_joints);
292
293 if (!updateAxisName()) {
294 return false;
295 }
296
297 return true;
298}
299
300
301void ControlBoard_nws_ros2::closeDevice()
302{
303 m_subdevice_ptr = nullptr;
304 m_subdevice_joints = 0;
305
306 m_times.clear();
307
308 // Clear all interfaces
309 m_iPositionControl = nullptr;
310 m_iEncodersTimed = nullptr;
311 m_iTorqueControl = nullptr;
312 m_iAxisInfo = nullptr;
313}
314
316{
317 if (!setDevice(poly)) {
318 return false;
319 }
320
322 if (!start()) {
323 yCError(CONTROLBOARD_ROS2) << "Error starting thread";
324 return false;
325 }
326
327 if(!m_msgs_name.empty())
328 {
329 if (m_msgs_name[0] != '/') {
331 }
332 if(!initRos2Control(m_msgs_name)){
333 yCError(CONTROLBOARD_ROS2) << "Error initializing the ROS2 control related topics and services";
334 RCLCPP_ERROR(m_node->get_logger(),"Error initializing the ROS2 control related topics and services");
335 return false;
336 }
337 }
338
339 if(m_spinner){
340 if(!m_spinner->start()){
341 yCError(CONTROLBOARD_ROS2) << "Error starting the spinner";
342 }
343 }
344
345 return true;
346}
347
349{
350 // Ensure that the device is not running
351 if (isRunning()) {
352 stop();
353 }
354
355 closeDevice();
356
357 return true;
358}
359
360bool ControlBoard_nws_ros2::updateAxisName()
361{
362 // IMPORTANT!! This function has to be called BEFORE the thread starts,
363 // the name has to be correct right from the first message!!
364
365 yCAssert(CONTROLBOARD_ROS2, m_iAxisInfo);
366
367 std::vector<std::string> tmpVect;
368 for (size_t i = 0; i < m_subdevice_joints; i++) {
369 std::string tmp;
370 bool ret = m_iAxisInfo->getAxisName(i, tmp);
371 if (!ret) {
372 yCError(CONTROLBOARD_ROS2, "Joint name for axis %zu not found!", i);
373 return false;
374 }
375 tmpVect.emplace_back(tmp);
376 }
377
378 yCAssert(CONTROLBOARD_ROS2, tmpVect.size() == m_subdevice_joints);
379
380 m_jointNames = tmpVect;
381
382 return true;
383}
384
386{
387 yCAssert(CONTROLBOARD_ROS2, m_iEncodersTimed);
388 yCAssert(CONTROLBOARD_ROS2, m_iAxisInfo);
389
390 bool positionsOk = m_iEncodersTimed->getEncodersTimed(m_ros_struct.position.data(), m_times.data());
392
393 bool speedsOk = m_iEncodersTimed->getEncoderSpeeds(m_ros_struct.velocity.data());
395
396 if (m_iTorqueControl) {
397 bool torqueOk = m_iTorqueControl->getTorques(m_ros_struct.effort.data());
399 }
400
401 // Update the port envelope time by averaging all timestamps
402 m_time.update(std::accumulate(m_times.begin(), m_times.end(), 0.0) / m_subdevice_joints);
404
405 // Data from HW have been gathered few lines before
407 for (size_t i = 0; i < m_subdevice_joints; i++) {
408 m_iAxisInfo->getJointType(i, jType);
410 m_ros_struct.position[i] = convertDegreesToRadians(m_ros_struct.position[i]);
411 m_ros_struct.velocity[i] = convertDegreesToRadians(m_ros_struct.velocity[i]);
412 }
413 }
414
415 m_ros_struct.name = m_jointNames;
416 m_ros_struct.header.stamp.sec = int(averageTime.getTime()); // FIXME
417 m_ros_struct.header.stamp.nanosec = static_cast<int>(1000000000 * (averageTime.getTime() - int(averageTime.getTime()))); // FIXME
418
419// m_ros_struct.header.stamp = m_node->get_clock()->now(); //@@@@@@@@@@@ FIXME: averageTime.getTime();
420// m_ros_struct.header.frame_id = m_frame_id; // FIXME
421
422
423 // FIXME
424 ++m_counter;
425// m_ros_struct.header.seq = m_counter++;
426
427 m_publisher->publish(m_ros_struct);
428}
#define M_PI
bool ret
double convertDegreesToRadians(double degrees)
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
bool open(yarp::os::Searchable &prop) override
Open the DeviceDriver.
void run() override
Loop function.
bool attach(yarp::dev::PolyDriver *poly) override
Attach to another object.
bool detach() override
Detach the object (you must have first called attach).
bool close() override
Close the DeviceDriver.
static rclcpp::Node::SharedPtr createNode(std::string name)
Definition Ros2Utils.cpp:9
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 getAxes(int *ax)=0
Get the number of controlled axes.
virtual bool getEncoderSpeeds(double *spds)=0
Read the instantaneous speed of all 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.
@ TraceType
Definition Log.h:92
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 base class for nested structures that can be searched.
Definition Searchable.h:31
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
bool stop()
Stop the thread.
Definition Thread.cpp:81
bool isRunning()
Returns true if the thread is running (Thread::start has been called successfully and the thread has ...
Definition Thread.cpp:105
bool start()
Start the new thread running.
Definition Thread.cpp:93
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:473
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:480
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
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