YARP
Yet Another Robot Platform
FrameTransformSet_nwc_ros.cpp
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
7
8#include <yarp/os/Log.h>
10#include <yarp/os/LogStream.h>
11
12using namespace yarp::dev;
13using namespace yarp::os;
14using namespace yarp::sig;
15using namespace yarp::math;
16
17namespace {
18YARP_LOG_COMPONENT(FRAMETRANSFORSETNWCROS, "yarp.device.frameTransformSet_nwc_ros")
19}
20
21//------------------------------------------------------------------------------------------------------------------------------
23PeriodicThread(tperiod),
24m_period(tperiod)
25{
26}
27
29{
31 yCError(FRAMETRANSFORSETNWCROS,"Error! YARP Network is not initialized");
32 return false;
33 }
34
35 bool okGeneral = config.check("GENERAL");
36 if(okGeneral)
37 {
38 yarp::os::Searchable& general_config = config.findGroup("GENERAL");
39 if (general_config.check("period"))
40 {
41 m_period = general_config.find("period").asFloat64();
42 setPeriod(m_period);
43 }
44 if (general_config.check("refresh_interval")) {m_refreshInterval = general_config.find("refresh_interval").asFloat64();}
45 if (general_config.check("asynch_pub")) {m_asynchPub = general_config.find("asynch_pub").asInt16();}
46 }
47 m_ftContainer.m_timeout = m_refreshInterval;
48
49 //ROS configuration
50 if (config.check("ROS"))
51 {
52 yCInfo(FRAMETRANSFORSETNWCROS, "Configuring ROS params");
53 Bottle ROS_config = config.findGroup("ROS");
54 if (ROS_config.check("ft_topic")) {
55 m_topic = ROS_config.find("ft_topic").asString();
56 }
57 if (ROS_config.check("ft_topic_static")) {
58 m_topic_static = ROS_config.find("ft_topic_static").asString();
59 }
60 if (ROS_config.check("ft_node")) {
61 m_nodeName = ROS_config.find("ft_node").asString();
62 }
63
64 //open ros publisher
65 if (m_rosNode == nullptr)
66 {
67 m_rosNode = new yarp::os::Node(m_nodeName);
68 }
69 if (!m_rosPublisherPort_tf_timed.topic(m_topic))
70 {
71 yCError(FRAMETRANSFORSETNWCROS) << "Unable to publish data on " << m_topic << " topic, check your yarp-ROS network configuration";
72 return false;
73 }
74 if (!m_rosPublisherPort_tf_static.topic(m_topic_static))
75 {
76 yCError(FRAMETRANSFORSETNWCROS) << "Unable to publish data on " << m_topic_static << " topic, check your yarp-ROS network configuration";
77 return false;
78 }
79 }
80 else
81 {
82 //no ROS options
83 yCWarning(FRAMETRANSFORSETNWCROS) << "ROS Group not configured";
84 return false;
85 }
86
87 start();
88
89 return true;
90}
91
93{
94 yCTrace(FRAMETRANSFORSETNWCROS, "Close");
95 if (PeriodicThread::isRunning())
96 {
97 PeriodicThread::stop();
98 }
99 m_rosPublisherPort_tf_timed.close();
100 m_rosPublisherPort_tf_static.close();
101 m_rosNode = nullptr;
102 return true;
103}
104
106{
107 std::lock_guard <std::mutex> lg(m_trf_mutex);
108 if(!m_ftContainer.checkAndRemoveExpired())
109 {
110 yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms");
111 return;
112 }
113 std::vector<yarp::math::FrameTransform> tempTfs;
114 if(!m_ftContainer.getTransforms(tempTfs))
115 {
116 yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)");
117 return;
118 }
119 publishFrameTransforms(tempTfs);
120}
121
122bool FrameTransformSet_nwc_ros::setTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
123{
124 std::lock_guard<std::mutex> lock(m_trf_mutex);
125 if(!m_ftContainer.setTransforms(transforms))
126 {
127 yCError(FRAMETRANSFORSETNWCROS,"Unable to set transforms");
128 return false;
129 }
130 if(m_asynchPub)
131 {
132 if(!m_ftContainer.checkAndRemoveExpired())
133 {
134 yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms");
135 return false;
136 }
137
138 std::vector<yarp::math::FrameTransform> tempTfs;
139 if(!m_ftContainer.getTransforms(tempTfs))
140 {
141 yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)");
142 return false;
143 }
144 publishFrameTransforms(tempTfs);
145 }
146 return true;
147}
148
150{
151 std::lock_guard<std::mutex> lock(m_trf_mutex);
152 if(!m_ftContainer.setTransform(t))
153 {
154 yCError(FRAMETRANSFORSETNWCROS,"Unable to set transform");
155 return false;
156 }
157 if(m_asynchPub)
158 {
159 if(!m_ftContainer.checkAndRemoveExpired())
160 {
161 yCError(FRAMETRANSFORSETNWCROS,"Unable to remove expired transforms");
162 return false;
163 }
164
165 std::vector<yarp::math::FrameTransform> tempTfs;
166 if(!m_ftContainer.getTransforms(tempTfs))
167 {
168 yCError(FRAMETRANSFORSETNWCROS,"Unable to get the transform vector)");
169 return false;
170 }
171 publishFrameTransforms(tempTfs);
172 }
173 return true;
174}
175
177{
178 output.child_frame_id = input.dst_frame_id;
179 output.header.frame_id = input.src_frame_id;
180 output.header.stamp = input.timestamp;
181 output.transform.rotation.x = input.rotation.x();
182 output.transform.rotation.y = input.rotation.y();
183 output.transform.rotation.z = input.rotation.z();
184 output.transform.rotation.w = input.rotation.w();
185 output.transform.translation.x = input.translation.tX;
186 output.transform.translation.y = input.translation.tY;
187 output.transform.translation.z = input.translation.tZ;
188}
189
190void FrameTransformSet_nwc_ros::publishFrameTransforms(const std::vector<yarp::math::FrameTransform>& transforms)
191{
192 static int rosMsgCounter = 0; // Ask for clarification!
193
194 yarp::rosmsg::tf2_msgs::TFMessage& rosOutTimedData = m_rosPublisherPort_tf_timed.prepare();
195 yarp::rosmsg::tf2_msgs::TFMessage& rosOutStaticData = m_rosPublisherPort_tf_static.prepare();
198 rosOutTimedData.transforms.clear();
199 rosOutStaticData.transforms.clear();
200
201 for(auto& tf : transforms)
202 {
203 if(tf.isStatic)
204 {
205 yarpTransformToROSTransform(tf,transform_static);
206 transform_static.header.seq = rosMsgCounter;
207 rosOutStaticData.transforms.push_back(transform_static);
208 }
209 else
210 {
211 yarpTransformToROSTransform(tf,transform_timed);
212 transform_timed.header.seq = rosMsgCounter;
213 rosOutTimedData.transforms.push_back(transform_timed);
214 }
215 }
216 m_rosPublisherPort_tf_timed.write();
217 m_rosPublisherPort_tf_static.write();
218
219 rosMsgCounter++;
220}
221
222bool FrameTransformSet_nwc_ros::deleteTransform(std::string t1, std::string t2)
223{
224 // Not yet implemented
225 yCError(FRAMETRANSFORSETNWCROS, "deleteTransform not yet implemented");
226 return false;
227}
228
230{
231 // Not yet implemented
232 yCError(FRAMETRANSFORSETNWCROS, "clearAll not yet implemented");
233 return false;
234}
float t
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.
bool close() override
Close the DeviceDriver.
bool clearAll() override
Delete all transforms in a storage.
void publishFrameTransforms(const std::vector< yarp::math::FrameTransform > &transforms)
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
void run() override
Loop function.
bool setTransform(const yarp::math::FrameTransform &transform) override
Save a frame transform in a storage.
bool setTransforms(const std::vector< yarp::math::FrameTransform > &transforms) override
Save some frame transforms in a storage.
bool deleteTransform(std::string t1, std::string t2) override
Delete a single transform in the storage.
void yarpTransformToROSTransform(const yarp::math::FrameTransform &input, yarp::rosmsg::geometry_msgs::TransformStamped &output)
FrameTransformSet_nwc_ros(double tperiod=0.010)
struct yarp::math::FrameTransform::Translation_t translation
double x() const
Definition: Quaternion.cpp:81
double z() const
Definition: Quaternion.cpp:91
double w() const
Definition: Quaternion.cpp:76
double y() const
Definition: Quaternion.cpp:86
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:64
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Definition: Bottle.cpp:277
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
Definition: Bottle.cpp:287
static bool checkNetwork()
Check if the YARP Network is up and running.
Definition: Network.cpp:1377
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 start()
Call this to start the thread.
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 write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
Definition: Publisher.h:148
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
Definition: Publisher.h:123
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 Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:222
virtual std::int16_t asInt16() const
Get 16-bit integer value.
Definition: Value.cpp:198
virtual std::string asString() const
Get string value.
Definition: Value.cpp:234
yarp::rosmsg::geometry_msgs::Transform transform
yarp::rosmsg::geometry_msgs::Quaternion rotation
Definition: Transform.h:35
yarp::rosmsg::geometry_msgs::Vector3 translation
Definition: Transform.h:34
yarp::conf::float64_t y
Definition: Vector3.h:38
yarp::conf::float64_t z
Definition: Vector3.h:39
yarp::conf::float64_t x
Definition: Vector3.h:37
yarp::rosmsg::TickTime stamp
Definition: Header.h:45
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
Definition: TFMessage.h:30
#define yCInfo(component,...)
Definition: LogComponent.h:171
#define yCError(component,...)
Definition: LogComponent.h:213
#define yCTrace(component,...)
Definition: LogComponent.h:84
#define yCWarning(component,...)
Definition: LogComponent.h:192
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:76
Definition: FrameGraph.h:19
For streams capable of holding different kinds of content, check what they actually have.
An interface to the operating system, including Port based communication.