|
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 |
|
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 |
|
|
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_ |
|
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
|
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
|
std::shared_ptr< rclcpp::Node > | node_ |
|
rclcpp_lifecycle::State | lifecycle_state_ |
|
unsigned int | update_rate_ = 0 |
|
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_topics | Flag to publish topics in local namespace. |
joints | Names of the joints to publish. |
interfaces | Names 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:
- joint_states (sensor_msgs::msg::JointState): Joint states related to movement (position, velocity, effort).
- dynamic_joint_states (control_msgs::msg::DynamicJointState): Joint states regardless of its interface type.