YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
FrameTransformGet_nwc_ros2 Class Reference

frameTransformGet_nwc_ros2: A ros network wrapper client that receives frame transforms from a ros2 topic and makes them available through an IFrameTransformStorageGet interface. More...

#include </home/runner/work/yarp-documentation/yarp-documentation/yarp/opt-modules/yarp-devices-ros2/src/devices/frameTransformGet_nwc_ros2/frameTransformGet_nwc_ros2.h>

+ Inheritance diagram for FrameTransformGet_nwc_ros2:

Public Member Functions

 ~FrameTransformGet_nwc_ros2 ()=default
 
bool open (yarp::os::Searchable &config) override
 Open the DeviceDriver.
 
bool close () override
 Close the DeviceDriver.
 
bool getTransforms (std::vector< yarp::math::FrameTransform > &transforms) const override
 Obtains all frame transforms saved in a storage.
 
void frameTransformTimedGet_callback (const tf2_msgs::msg::TFMessage::SharedPtr msg)
 
void frameTransformStaticGet_callback (const tf2_msgs::msg::TFMessage::SharedPtr msg)
 
void ros2TransformToYARP (const geometry_msgs::msg::TransformStamped &input, yarp::math::FrameTransform &output, bool isStatic)
 
bool updateBuffer (const std::vector< geometry_msgs::msg::TransformStamped > &transforms, bool areStatic)
 
bool setTransform (const yarp::math::FrameTransform &transform)
 
- Public Member Functions inherited from yarp::dev::DeviceDriver
 DeviceDriver ()
 
 DeviceDriver (const DeviceDriver &other)=delete
 
 DeviceDriver (DeviceDriver &&other) noexcept=delete
 
DeviceDriveroperator= (const DeviceDriver &other)=delete
 
DeviceDriveroperator= (DeviceDriver &&other) noexcept=delete
 
virtual ~DeviceDriver ()
 
virtual std::string id () const
 Return the id assigned to the PolyDriver.
 
virtual void setId (const std::string &id)
 Set the id for this device.
 
template<class T >
bool view (T *&x)
 Get an interface to the device driver.
 
virtual DeviceDrivergetImplementation ()
 Some drivers are bureaucrats, pointing at others.
 
- Public Member Functions inherited from yarp::dev::IFrameTransformStorageGet
virtual ~IFrameTransformStorageGet ()
 

Public Attributes

Ros2Spinnerm_spinner {nullptr}
 

Detailed Description

frameTransformGet_nwc_ros2: A ros network wrapper client that receives frame transforms from a ros2 topic and makes them available through an IFrameTransformStorageGet interface.

See FrameTransform: start all the required devices needed for transforming frames for additional info.

Parameters

Parameters required by this device are shown in class: FrameTransformGet_nwc_ros2_ParamsParser

N.B. pay attention to the difference between tf and ft

Example of configuration file using .ini format.

device frameTransformGet_nwc_ros2
[GENERAL]
period 0.05
refresh_interval 0.2
[ROS]
ft_topic /tf
ft_topic_static /tf_static
ft_node /tfNodeGet

Definition at line 61 of file frameTransformGet_nwc_ros2.h.

Constructor & Destructor Documentation

◆ ~FrameTransformGet_nwc_ros2()

FrameTransformGet_nwc_ros2::~FrameTransformGet_nwc_ros2 ( )
default

Member Function Documentation

◆ close()

bool FrameTransformGet_nwc_ros2::close ( )
overridevirtual

Close the DeviceDriver.

Returns
true/false on success/failure.

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 50 of file frameTransformGet_nwc_ros2.cpp.

◆ frameTransformStaticGet_callback()

void FrameTransformGet_nwc_ros2::frameTransformStaticGet_callback ( const tf2_msgs::msg::TFMessage::SharedPtr  msg)

Definition at line 77 of file frameTransformGet_nwc_ros2.cpp.

◆ frameTransformTimedGet_callback()

void FrameTransformGet_nwc_ros2::frameTransformTimedGet_callback ( const tf2_msgs::msg::TFMessage::SharedPtr  msg)

Definition at line 70 of file frameTransformGet_nwc_ros2.cpp.

◆ getTransforms()

bool FrameTransformGet_nwc_ros2::getTransforms ( std::vector< yarp::math::FrameTransform > &  transforms) const
overridevirtual

Obtains all frame transforms saved in a storage.

Parameters
transformsthe returned list of frame transforms
Returns
true/false

Implements yarp::dev::IFrameTransformStorageGet.

Definition at line 58 of file frameTransformGet_nwc_ros2.cpp.

◆ open()

bool FrameTransformGet_nwc_ros2::open ( yarp::os::Searchable config)
overridevirtual

Open the DeviceDriver.

Parameters
configis a list of parameters for the device. Which parameters are effective for your device can vary. See device invocation examples. If there is no example for your device, you can run the "yarpdev" program with the verbose flag set to probe what parameters the device is checking. If that fails too, you'll need to read the source code (please nag one of the yarp developers to add documentation for your device).
Returns
true/false upon success/failure

Reimplemented from yarp::dev::DeviceDriver.

Definition at line 22 of file frameTransformGet_nwc_ros2.cpp.

◆ ros2TransformToYARP()

void FrameTransformGet_nwc_ros2::ros2TransformToYARP ( const geometry_msgs::msg::TransformStamped &  input,
yarp::math::FrameTransform output,
bool  isStatic 
)

Definition at line 84 of file frameTransformGet_nwc_ros2.cpp.

◆ setTransform()

bool FrameTransformGet_nwc_ros2::setTransform ( const yarp::math::FrameTransform transform)

◆ updateBuffer()

bool FrameTransformGet_nwc_ros2::updateBuffer ( const std::vector< geometry_msgs::msg::TransformStamped > &  transforms,
bool  areStatic 
)

Definition at line 101 of file frameTransformGet_nwc_ros2.cpp.

Member Data Documentation

◆ m_spinner

Ros2Spinner* FrameTransformGet_nwc_ros2::m_spinner {nullptr}

Definition at line 74 of file frameTransformGet_nwc_ros2.h.


The documentation for this class was generated from the following files: