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
68bool FrameTransformSet_nwc_ros2::setTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
69{
70 std::lock_guard<std::mutex> lock(m_trf_mutex);
71 if(!m_ftContainer.setTransforms(transforms))
72 {
73 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transforms");
74 return false;
75 }
77 {
79 {
80 yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
81 return false;
82 }
83 }
84 return true;
85}
86
88{
89 std::lock_guard<std::mutex> lock(m_trf_mutex);
90 if(!m_ftContainer.setTransform(t))
91 {
92 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to set transform");
93 return false;
94 }
96 {
98 {
99 yCError(FRAMETRANSFORMSETNWCROS2,"Error while publishing transforms");
100 return false;
101 }
102 }
103 return true;
104}
105
106void FrameTransformSet_nwc_ros2::ros2TimeFromYarp(double yarpTime, builtin_interfaces::msg::Time& ros2Time)
107{
108 uint64_t time;
111 sec_part = int(yarpTime); // (time / 1000000000UL);
112 nsec_part = (yarpTime - sec_part)*1000000000UL;
113 ros2Time.sec = sec_part;
114 ros2Time.nanosec = (uint32_t)nsec_part;
115}
116
117void FrameTransformSet_nwc_ros2::yarpTransformToROS2Transform(const yarp::math::FrameTransform &input, geometry_msgs::msg::TransformStamped& output)
118{
119 builtin_interfaces::msg::Time tempStamp;
120 std_msgs::msg::Header tempHeader;
121 geometry_msgs::msg::Transform tempTf;
122 geometry_msgs::msg::Vector3 tempTransl;
123 geometry_msgs::msg::Quaternion tempRotation;
124
125 tempTransl.x = input.translation.tX;
126 tempTransl.y = input.translation.tY;
127 tempTransl.z = input.translation.tZ;
128
129 tempRotation.w = input.rotation.w();
130 tempRotation.x = input.rotation.x();
131 tempRotation.y = input.rotation.y();
132 tempRotation.z = input.rotation.z();
133
134 tempTf.rotation = tempRotation;
135 tempTf.translation = tempTransl;
136
138 tempHeader.stamp = tempStamp;
139 tempHeader.frame_id = input.src_frame_id;
140
141 output.header = tempHeader;
142 output.child_frame_id = input.dst_frame_id;
143 output.transform = tempTf;
144}
145
147{
148 if(!m_ftContainer.checkAndRemoveExpired())
149 {
150 yCError(FRAMETRANSFORMSETNWCROS2,"Unable to remove expired transforms");
151 return false;
152 }
153 std::vector<yarp::math::FrameTransform> fromGet;
154 m_ftContainer.getTransforms(fromGet);
155 tf2_msgs::msg::TFMessage toPublish_timed;
156 tf2_msgs::msg::TFMessage toPublish_static;
157 std::vector<geometry_msgs::msg::TransformStamped> content_timed;
158 std::vector<geometry_msgs::msg::TransformStamped> content_static;
159 for(auto &ft : fromGet)
160 {
161 geometry_msgs::msg::TransformStamped tempTfs;
163 if(!ft.isStatic) {
164 content_timed.push_back(tempTfs);
165 }else {
166 content_static.push_back(tempTfs);
167 }
168 }
169
170 toPublish_timed.transforms = content_timed;
171 toPublish_static.transforms = content_static;
172 if (content_timed.size() > 0) {
173 m_publisherFtTimed->publish(toPublish_timed);
174 }
175 if (content_static.size() > 0) {
176 m_publisherFtStatic->publish(toPublish_static);
177 }
178
179 return true;
180}
181
182bool FrameTransformSet_nwc_ros2::deleteTransform(std::string t1, std::string t2)
183{
184 // Not yet implemented
185 yCError(FRAMETRANSFORMSETNWCROS2, "deleteTransform not yet implemented");
186 return false;
187}
188
190{
191 // Not yet implemented
192 yCError(FRAMETRANSFORMSETNWCROS2, "clearAll not yet implemented");
193 return false;
194}
float t
bool parseParams(const yarp::os::Searchable &config) override
Parse the DeviceDriver parameters.
FrameTransformSet_nwc_ros2(double tperiod=0.010)
bool setTransforms(const std::vector< yarp::math::FrameTransform > &transforms) override
Save some frame transforms in a storage.
bool clearAll() override
Delete all transforms in a storage.
void ros2TimeFromYarp(double yarpTime, builtin_interfaces::msg::Time &ros2Time)
bool 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.
bool setTransform(const yarp::math::FrameTransform &transform) override
Save a frame transform in a storage.
void yarpTransformToROS2Transform(const yarp::math::FrameTransform &input, geometry_msgs::msg::TransformStamped &output)
static rclcpp::Node::SharedPtr createNode(std::string name)
Definition Ros2Utils.cpp:9
bool setTransform(const yarp::math::FrameTransform &transform) override
Save a frame transform in a storage.
bool getTransforms(std::vector< yarp::math::FrameTransform > &transforms) const override
Obtains all frame transforms saved in a storage.
bool setTransforms(const std::vector< yarp::math::FrameTransform > &transforms) override
Save some frame transforms in a storage.
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.
Definition jointData.cpp:13
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.