Modulo 5.0.0
Loading...
Searching...
No Matches
modulo_core::JointPositionsBroadcaster Class Reference

The JointPositionsBroadcaster is a TF2 style class that publishes a collection of JointPositions messages to the fixed /joint_positions topic. More...

#include <JointPositionsBroadcaster.hpp>

Public Member Functions

template<class NodeT , class AllocatorT = std::allocator<void>>
 JointPositionsBroadcaster (NodeT &&node, const rclcpp::QoS &qos=rclcpp::QoS(1).transient_local(), const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=detail::get_default_joint_positions_options< rclcpp::PublisherOptionsWithAllocator< AllocatorT > >())
 Constructor of the JointPositionsBroadcaster with a node.
 
template<class AllocatorT = std::allocator<void>>
 JointPositionsBroadcaster (rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, const rclcpp::QoS &qos=rclcpp::QoS(1).transient_local(), const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options=detail::get_default_joint_positions_options< rclcpp::PublisherOptionsWithAllocator< AllocatorT > >())
 Constructor of the JointPositionsBroadcaster with node interfaces.
 
template<typename T >
void send (const T &joint_positions)
 Send a JointPositions object.
 
template<typename T >
void send (const std::vector< T > &joint_positions)
 Send a vector of JointPositions objects.
 
template<>
void send (const std::vector< modulo_interfaces::msg::JointPositions > &joint_positions)
 
template<>
void send (const std::vector< state_representation::JointPositions > &joint_positions)
 

Detailed Description

The JointPositionsBroadcaster is a TF2 style class that publishes a collection of JointPositions messages to the fixed /joint_positions topic.

Definition at line 21 of file JointPositionsBroadcaster.hpp.

Constructor & Destructor Documentation

◆ JointPositionsBroadcaster() [1/2]

template<class NodeT , class AllocatorT = std::allocator<void>>
modulo_core::JointPositionsBroadcaster::JointPositionsBroadcaster ( NodeT && node,
const rclcpp::QoS & qos = rclcpp::QoS(1).transient_local(),
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > & options = detail::get_default_joint_positions_options<rclcpp::PublisherOptionsWithAllocator<AllocatorT>>() )
inline

Constructor of the JointPositionsBroadcaster with a node.

Definition at line 27 of file JointPositionsBroadcaster.hpp.

◆ JointPositionsBroadcaster() [2/2]

template<class AllocatorT = std::allocator<void>>
modulo_core::JointPositionsBroadcaster::JointPositionsBroadcaster ( rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters,
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
const rclcpp::QoS & qos = rclcpp::QoS(1).transient_local(),
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > & options = detail::get_default_joint_positions_options<rclcpp::PublisherOptionsWithAllocator<AllocatorT>>() )
inline

Constructor of the JointPositionsBroadcaster with node interfaces.

Definition at line 39 of file JointPositionsBroadcaster.hpp.

Member Function Documentation

◆ send() [1/4]

template<>
void modulo_core::JointPositionsBroadcaster::send ( const std::vector< modulo_interfaces::msg::JointPositions > & joint_positions)

Definition at line 6 of file JointPositionsBroadcaster.cpp.

◆ send() [2/4]

template<>
void modulo_core::JointPositionsBroadcaster::send ( const std::vector< state_representation::JointPositions > & joint_positions)

Definition at line 14 of file JointPositionsBroadcaster.cpp.

◆ send() [3/4]

template<typename T >
void modulo_core::JointPositionsBroadcaster::send ( const std::vector< T > & joint_positions)

Send a vector of JointPositions objects.

Template Parameters
TType of the JointPositions objects
Parameters
joint_positionsThe vector of JointPositions objects to send

◆ send() [4/4]

template<typename T >
void modulo_core::JointPositionsBroadcaster::send ( const T & joint_positions)
inline

Send a JointPositions object.

Template Parameters
TType of the JointPositions object
Parameters
joint_positionsThe JointPositions object to send

Definition at line 76 of file JointPositionsBroadcaster.hpp.


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