40 m_publisherFtTimed = m_node->create_publisher<tf2_msgs::msg::TFMessage>(
m_ROS2_ft_topic, 10);
60 std::lock_guard <std::mutex>
lg(m_trf_mutex);
70 std::lock_guard<std::mutex> lock(m_trf_mutex);
89 std::lock_guard<std::mutex> lock(m_trf_mutex);
121 geometry_msgs::msg::Transform
tempTf;
143 output.transform =
tempTf;
153 std::vector<yarp::math::FrameTransform>
fromGet;
157 std::vector<geometry_msgs::msg::TransformStamped>
content_timed;
161 geometry_msgs::msg::TransformStamped
tempTfs;
static rclcpp::Node::SharedPtr createNode(std::string name)
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.
#define yCError(component,...)
#define yCTrace(component,...)
#define YARP_LOG_COMPONENT(name,...)
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.
An interface to the operating system, including Port based communication.