ros2_control - rolling
Loading...
Searching...
No Matches
Classes | 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]

Classes

struct  JointStateData
 

Public Member Functions

controller_interface::InterfaceConfiguration command_interface_configuration () const override
 Get configuration for controller's required command interfaces.
 
controller_interface::InterfaceConfiguration state_interface_configuration () const override
 Get configuration for controller's required state interfaces.
 
controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
 Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.
 
controller_interface::CallbackReturn on_init () override
 Extending interface with initialization method which is individual for each controller.
 
controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
- Public Member Functions inherited from controller_interface::ControllerInterface
bool is_chainable () const final
 Controller is not chainable.
 
std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces () final
 A non-chainable controller doesn't export any state interfaces.
 
std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces () final
 Controller has no reference interfaces.
 
bool set_chained_mode (bool chained_mode) final
 Controller is not chainable, therefore no chained mode can be set.
 
bool is_in_chained_mode () const final
 Controller can not be in chained mode.
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller.
 
virtual void release_interfaces ()
 Method that releases the Loaned interfaces from the controller.
 
return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
return_type init (const controller_interface::ControllerInterfaceParams &params)
 
const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
ControllerUpdateStatus trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period)
 Trigger update method. This method is used by the controller_manager to trigger the update method of the controller. The method is used to trigger the update method of the controller synchronously or asynchronously, based on the controller configuration. The method called in the (real-time) control loop.
 
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 Get the current lifecycle state of the controller node.
 
uint8_t get_lifecycle_id () const
 Get the lifecycle id of the controller node that is cached internally to avoid calls to get_lifecycle_state() in the real-time control loop.
 
unsigned int get_update_rate () const
 
bool is_async () const
 
const std::string & get_robot_description () const
 
const std::unordered_map< std::string, joint_limits::JointLimits > & get_hard_joint_limits () const
 Get the unordered map of joint limits that are defined in the robot description.
 
const std::unordered_map< std::string, joint_limits::SoftJointLimits > & get_soft_joint_limits () const
 Get the unordered map of soft joint limits that are defined in the robot description.
 
virtual rclcpp::NodeOptions define_custom_node_options () const
 Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the controller upon loading the controller.
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type.
 
void wait_for_trigger_update_to_finish ()
 Method to wait for any running async update cycle to finish after finishing the current cycle. This is needed to be called before deactivating the controller by the controller_manager, so that the interfaces still exist when the controller finishes its cycle and then it's exits.
 
void prepare_for_deactivation ()
 Method to prepare the controller for deactivation. This method is called by the controller manager before deactivating the controller. The method is used to prepare the controller for deactivation, e.g., to stop triggering the update cycles further. This method is especially needed for controllers running in async mode and different frequency than the control manager.
 
std::string get_name () const
 
void enable_introspection (bool enable)
 Enable or disable introspection of the controller.
 

Protected Member Functions

bool init_joint_data ()
 
void init_auxiliary_data ()
 
void init_joint_state_msg ()
 
bool use_all_available_interfaces () const
 
bool use_urdf_joint_interfaces () const
 

Protected Attributes

std::shared_ptr< ParamListener > param_listener_
 
Params params_
 
std::unordered_map< std::string, std::string > map_interface_to_joint_state_
 
std::string frame_id_
 
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_
 
sensor_msgs::msg::JointState joint_state_msg_
 
std::unordered_map< std::string, std::unordered_map< std::string, double > > name_if_value_mapping_
 
urdf::Model model_
 
bool is_model_loaded_ = false
 
std::vector< double * > mapped_values_
 
std::vector< JointStateDatajoint_states_data_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 Loaned command interfaces.
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 Loaned state interfaces.
 
pal_statistics::RegistrationsRAII stats_registrations_
 

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

Get configuration for controller's required command interfaces.

Method used by the controller_manager to get the set of command interfaces used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the command_interfaces_ member.

Returns
configuration of command interfaces.

Implements controller_interface::ControllerInterfaceBase.

◆ 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()

controller_interface::CallbackReturn joint_state_broadcaster::JointStateBroadcaster::on_init ( )
overridevirtual

Extending interface with initialization method which is individual for each controller.

Implements controller_interface::ControllerInterfaceBase.

◆ state_interface_configuration()

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

Get configuration for controller's required state interfaces.

Method used by the controller_manager to get the set of state interface used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the state_interfaces_ member.

Returns
configuration of state interfaces.

Implements controller_interface::ControllerInterfaceBase.

◆ update()

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

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time since the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.


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