YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
frameTransformSet_nwc_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
7#include <yarp/os/Log.h>
9#include <yarp/os/LogStream.h>
10
11using namespace std;
12using namespace yarp::dev;
13using namespace yarp::os;
14using namespace yarp::sig;
15using namespace yarp::math;
16
17namespace {
18YARP_LOG_COMPONENT(FRAMETRANSFORMSETNWCROS2, "yarp.device.frameTransformSet_nwc_ros2")
19}
20
21//------------------------------------------------------------------------------------------------------------------------------
22
27
29{
31 yCError(FRAMETRANSFORMSETNWCROS2,"Error! YARP Network is not initialized");
32 return false;
33 }
34
35 parseParams(config);
36
40 m_publisherFtTimed = m_node->create_publisher<tf2_msgs::msg::TFMessage>(m_ROS2_ft_topic, 10);
41 m_publisherFtStatic = m_node->create_publisher<tf2_msgs::msg::TFMessage>(m_ROS2_ft_topic_static, rclcpp::QoS(10).reliable().durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL));
42
43 start();
44
45 return true;
46}
47
49{
52 {
54 }
55 return true;
56}
57
59{
60 std::lock_guard <std::mutex> lg(m_trf_mutex);
62 {
63 yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
64 }
65 return;
66}
67
68yarp::dev::ReturnValue FrameTransformSet_nwc_ros2::setTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
69{
70 std::lock_guard<std::mutex> lock(m_trf_mutex);
71 yarp::dev::ReturnValue ret = m_ftContainer.setTransforms(transforms);
72 if(!ret)
73 {
74 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transforms. Error: %s",ret.toString().c_str());
75 return ret;
76 }
78 {
80 {
81 yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
83 }
84 }
86}
87
89{
90 std::lock_guard<std::mutex> lock(m_trf_mutex);
91 yarp::dev::ReturnValue ret = m_ftContainer.setTransform(t);
92 if(!ret)
93 {
94 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transform. Error: %s",ret.toString().c_str());
95 return ret;
96 }
98 {
100 {
101 yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
103 }
104 }
106}
107
108void FrameTransformSet_nwc_ros2::ros2TimeFromYarp(double yarpTime, builtin_interfaces::msg::Time& ros2Time)
109{
112 sec_part = int(yarpTime); // (time / 1000000000UL);
113 nsec_part = (yarpTime - sec_part)*1000000000UL;
114 ros2Time.sec = sec_part;
115 ros2Time.nanosec = (uint32_t)nsec_part;
116}
117
118void FrameTransformSet_nwc_ros2::yarpTransformToROS2Transform(const yarp::math::FrameTransform &input, geometry_msgs::msg::TransformStamped& output)
119{
120 builtin_interfaces::msg::Time tempStamp;
121 std_msgs::msg::Header tempHeader;
122 geometry_msgs::msg::Transform tempTf;
123 geometry_msgs::msg::Vector3 tempTransl;
124 geometry_msgs::msg::Quaternion tempRotation;
125
126 tempTransl.x = input.translation.tX;
127 tempTransl.y = input.translation.tY;
128 tempTransl.z = input.translation.tZ;
129
130 tempRotation.w = input.rotation.w();
131 tempRotation.x = input.rotation.x();
132 tempRotation.y = input.rotation.y();
133 tempRotation.z = input.rotation.z();
134
135 tempTf.rotation = tempRotation;
136 tempTf.translation = tempTransl;
137
139 tempHeader.stamp = tempStamp;
140 tempHeader.frame_id = input.src_frame_id;
141
142 output.header = tempHeader;
143 output.child_frame_id = input.dst_frame_id;
144 output.transform = tempTf;
145}
146
148{
149 if(!m_ftContainer.checkAndRemoveExpired())
150 {
151 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to remove expired transforms");
152 return false;
153 }
154 std::vector<yarp::math::FrameTransform> fromGet;
155 m_ftContainer.getTransforms(fromGet);
156 tf2_msgs::msg::TFMessage toPublish_timed;
157 tf2_msgs::msg::TFMessage toPublish_static;
158 std::vector<geometry_msgs::msg::TransformStamped> content_timed;
159 std::vector<geometry_msgs::msg::TransformStamped> content_static;
160 for(auto &ft : fromGet)
161 {
162 geometry_msgs::msg::TransformStamped tempTfs;
164 if(!ft.isStatic) {
165 content_timed.push_back(tempTfs);
166 }else {
167 content_static.push_back(tempTfs);
168 }
169 }
170
171 toPublish_timed.transforms = content_timed;
172 toPublish_static.transforms = content_static;
173 if (content_timed.size() > 0) {
174 m_publisherFtTimed->publish(toPublish_timed);
175 }
176 if (content_static.size() > 0) {
177 m_publisherFtStatic->publish(toPublish_static);
178 }
179
180 return true;
181}
182
184{
185 // Not yet implemented
186 yCError(FRAMETRANSFORMSETNWCROS2, "deleteTransform not yet implemented");
188}
189
bool ret
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
FrameTransformSet_nwc_ros2(double tperiod=0.010)
yarp::dev::ReturnValue clearAll() override
Delete all transforms in a storage.
void ros2TimeFromYarp(double yarpTime, builtin_interfaces::msg::Time &ros2Time)
yarp::dev::ReturnValue setTransform(const yarp::math::FrameTransform &transform) override
Save a frame transform in a storage.
yarp::dev::ReturnValue setTransforms(const std::vector< yarp::math::FrameTransform > &transforms) override
Save some frame transforms in a storage.
yarp::dev::ReturnValue deleteTransform(std::string t1, std::string t2) override
Delete a single transform in the storage.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
void run() override
Loop function.
bool close() override
Close the DeviceDriver.
void yarpTransformToROS2Transform(const yarp::math::FrameTransform &input, geometry_msgs::msg::TransformStamped &output)
static rclcpp::Node::SharedPtr createNode(std::string name)
Definition Ros2Utils.cpp:9
yarp::dev::ReturnValue getTransforms(std::vector< yarp::math::FrameTransform > &transforms) const override
Obtains all frame transforms saved in a storage.
yarp::dev::ReturnValue setTransform(const yarp::math::FrameTransform &transform) override
Save a frame transform in a storage.
yarp::dev::ReturnValue setTransforms(const std::vector< yarp::math::FrameTransform > &transforms) override
Save some frame transforms in a storage.
@ return_value_error_generic
Method was successfully executed.
struct yarp::math::FrameTransform::Translation_t translation
A mini-server for performing network communication in the background.
static bool checkNetwork()
Check if the YARP Network is up and running.
Definition Network.cpp:1370
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
#define yCError(component,...)
#define yCTrace(component,...)
#define YARP_LOG_COMPONENT(name,...)
STL namespace.
For streams capable of holding different kinds of content, check what they actually have.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition Time.cpp:121
An interface to the operating system, including Port based communication.