31 yCError(FRAMETRANSFORSETNWCROS,
"Error! YARP Network is not initialized");
35 bool okGeneral = config.
check(
"GENERAL");
39 if (general_config.
check(
"period"))
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();}
47 m_ftContainer.
m_timeout = m_refreshInterval;
50 if (config.
check(
"ROS"))
52 yCInfo(FRAMETRANSFORSETNWCROS,
"Configuring ROS params");
54 if (ROS_config.
check(
"ft_topic")) {
57 if (ROS_config.
check(
"ft_topic_static")) {
58 m_topic_static = ROS_config.
find(
"ft_topic_static").
asString();
60 if (ROS_config.
check(
"ft_node")) {
65 if (m_rosNode ==
nullptr)
69 if (!m_rosPublisherPort_tf_timed.
topic(m_topic))
71 yCError(FRAMETRANSFORSETNWCROS) <<
"Unable to publish data on " << m_topic <<
" topic, check your yarp-ROS network configuration";
74 if (!m_rosPublisherPort_tf_static.
topic(m_topic_static))
76 yCError(FRAMETRANSFORSETNWCROS) <<
"Unable to publish data on " << m_topic_static <<
" topic, check your yarp-ROS network configuration";
83 yCWarning(FRAMETRANSFORSETNWCROS) <<
"ROS Group not configured";
94 yCTrace(FRAMETRANSFORSETNWCROS,
"Close");
95 if (PeriodicThread::isRunning())
97 PeriodicThread::stop();
99 m_rosPublisherPort_tf_timed.
close();
100 m_rosPublisherPort_tf_static.
close();
107 std::lock_guard <std::mutex> lg(m_trf_mutex);
110 yCError(FRAMETRANSFORSETNWCROS,
"Unable to remove expired transforms");
113 std::vector<yarp::math::FrameTransform> tempTfs;
116 yCError(FRAMETRANSFORSETNWCROS,
"Unable to get the transform vector)");
124 std::lock_guard<std::mutex> lock(m_trf_mutex);
127 yCError(FRAMETRANSFORSETNWCROS,
"Unable to set transforms");
134 yCError(FRAMETRANSFORSETNWCROS,
"Unable to remove expired transforms");
138 std::vector<yarp::math::FrameTransform> tempTfs;
141 yCError(FRAMETRANSFORSETNWCROS,
"Unable to get the transform vector)");
151 std::lock_guard<std::mutex> lock(m_trf_mutex);
154 yCError(FRAMETRANSFORSETNWCROS,
"Unable to set transform");
161 yCError(FRAMETRANSFORSETNWCROS,
"Unable to remove expired transforms");
165 std::vector<yarp::math::FrameTransform> tempTfs;
168 yCError(FRAMETRANSFORSETNWCROS,
"Unable to get the transform vector)");
192 static int rosMsgCounter = 0;
201 for(
auto&
tf : transforms)
206 transform_static.
header.
seq = rosMsgCounter;
207 rosOutStaticData.
transforms.push_back(transform_static);
212 transform_timed.
header.
seq = rosMsgCounter;
213 rosOutTimedData.
transforms.push_back(transform_timed);
216 m_rosPublisherPort_tf_timed.
write();
217 m_rosPublisherPort_tf_static.
write();
225 yCError(FRAMETRANSFORSETNWCROS,
"deleteTransform not yet implemented");
232 yCError(FRAMETRANSFORSETNWCROS,
"clearAll not yet implemented");
A simple collection of objects that can be described and transmitted in a portable way.
bool check(const std::string &key) const override
Check if there exists a property of the given name.
Value & find(const std::string &key) const override
Gets a value corresponding to a given keyword.
static bool checkNetwork()
Check if the YARP Network is up and running.
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.
bool topic(const std::string &name)
Set topic to publish to.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
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.
virtual std::int16_t asInt16() const
Get 16-bit integer value.
virtual std::string asString() const
Get string value.
std::vector< yarp::rosmsg::geometry_msgs::TransformStamped > transforms
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
An interface to the operating system, including Port based communication.