ros2_control - galactic
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
joint_state_broadcaster::JointStateBroadcaster Class Reference

Joint State Broadcaster for all or some state in a ros2_control system. More...

#include <joint_state_broadcaster.hpp>

Inheritance diagram for joint_state_broadcaster::JointStateBroadcaster:
Inheritance graph
[legend]
Collaboration diagram for joint_state_broadcaster::JointStateBroadcaster:
Collaboration graph
[legend]

Public Member Functions

JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
 
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
 
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 
JOINT_STATE_BROADCASTER_PUBLIC CallbackReturn on_init () override
 
JOINT_STATE_BROADCASTER_PUBLIC CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_STATE_BROADCASTER_PUBLIC CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
JOINT_STATE_BROADCASTER_PUBLIC CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 
CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 
virtual CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name)
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp::Node > get_node ()
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type.
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown ()
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 

Protected Member Functions

bool init_joint_data ()
 
void init_joint_state_msg ()
 
void init_dynamic_joint_state_msg ()
 
bool use_all_available_interfaces () const
 

Protected Attributes

bool use_local_topics_
 
std::vector< std::string > joints_
 
std::vector< std::string > interfaces_
 
std::unordered_map< std::string, std::string > map_interface_to_joint_state_
 
std::vector< std::string > joint_names_
 
std::shared_ptr< rclcpp::Publisher< sensor_msgs::msg::JointState > > joint_state_publisher_
 
std::shared_ptr< realtime_tools::RealtimePublisher< sensor_msgs::msg::JointState > > realtime_joint_state_publisher_
 
std::unordered_map< std::string, std::unordered_map< std::string, double > > name_if_value_mapping_
 
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::DynamicJointState > > dynamic_joint_state_publisher_
 
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::msg::DynamicJointState > > realtime_dynamic_joint_state_publisher_
 
- Protected Attributes inherited from controller_interface::ControllerInterface
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 
std::shared_ptr< rclcpp::Node > node_
 
rclcpp_lifecycle::State lifecycle_state_
 
unsigned int update_rate_ = 0
 

Detailed Description

Joint State Broadcaster for all or some state in a ros2_control system.

JointStateBroadcaster publishes state interfaces from ros2_control as ROS messages. There is a possibility to publish all available states (typical use), or only specific ones. The latter is, for example, used when hardware provides multiple measurement sources for some of its states, e.g., position. It is possible to define a mapping of measurements from different sources stored in custom interfaces to standard dynamic names in JointState message. If "joints" or "interfaces" parameter is empty, all available states are published.

Parameters
use_local_topicsFlag to publish topics in local namespace.
jointsNames of the joints to publish.
interfacesNames of interfaces to publish.
map_interface_to_joint_state.{HW_IF_POSITION|HW_IF_VELOCITY|HW_IF_EFFORT}mapping between custom interface names and standard names in sensor_msgs::msg::JointState message.

Publishes to:

Member Function Documentation

◆ command_interface_configuration()

controller_interface::InterfaceConfiguration joint_state_broadcaster::JointStateBroadcaster::command_interface_configuration ( ) const
overridevirtual

◆ init_joint_state_msg()

void joint_state_broadcaster::JointStateBroadcaster::init_joint_state_msg ( )
protected
Note
joint_state_msg publishes position, velocity and effort for all joints, with at least one of these interfaces, the rest are omitted from this message

◆ on_init()

CallbackReturn joint_state_broadcaster::JointStateBroadcaster::on_init ( )
overridevirtual

◆ state_interface_configuration()

controller_interface::InterfaceConfiguration joint_state_broadcaster::JointStateBroadcaster::state_interface_configuration ( ) const
overridevirtual

◆ update()

controller_interface::return_type joint_state_broadcaster::JointStateBroadcaster::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

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