46 m_ftContainer.
m_timeout = m_refreshInterval;
49 if (config.
check(
"ROS"))
54 m_topic =
ROS_config.find(
"ft_topic").asString();
57 m_topic_static =
ROS_config.find(
"ft_topic_static").asString();
60 m_nodeName =
ROS_config.find(
"ft_node").asString();
64 if (m_rosNode ==
nullptr)
68 if (!m_rosSubscriberPort_tf_timed.
topic(m_topic))
74 if (!m_rosSubscriberPort_tf_static.
topic(m_topic_static))
79 m_rosSubscriberPort_tf_static.
setStrict();
100 m_rosSubscriberPort_tf_timed.
close();
101 m_rosSubscriberPort_tf_static.
close();
108 std::lock_guard <std::mutex>
lg(m_trf_mutex);
119 std::lock_guard<std::mutex> lock(m_trf_mutex);
150 output.
rotation.
x() = input.transform.rotation.x;
151 output.
rotation.
y() = input.transform.rotation.y;
152 output.
rotation.
z() = input.transform.rotation.z;
153 output.
rotation.
w() = input.transform.rotation.w;
154 output.
translation.tX = input.transform.translation.x;
155 output.
translation.tY = input.transform.translation.y;
156 output.
translation.tZ = input.transform.translation.z;
168 std::vector <yarp::rosmsg::geometry_msgs::TransformStamped>
tfs =
rosInData_timed->transforms;
183 std::vector <yarp::rosmsg::geometry_msgs::TransformStamped>
tfs =
rosInData_static->transforms;
A simple collection of objects that can be described and transmitted in a portable way.
A mini-server for performing network communication in the background.
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 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.
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.
T * read(bool shouldWait=true)
Read a message from the port.
void close() override
Stop port activity.
void setStrict(bool strict=true)
bool topic(const std::string &name)
Set topic to subscribe to.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define yCWarning(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
An interface to the operating system, including Port based communication.