Class StateInterfacesBroadcaster
Defined in File state_interfaces_broadcaster.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class StateInterfacesBroadcaster : public controller_interface::ControllerInterface
State Interfaces Broadcaster for selected state interfaces in a ros2_control system.
StateInterfacesBroadcaster publishes the selected state interfaces from ros2_control as ROS messages.
Publishes to:
~/names (control_msgs::msg::Keys): The list of the interface names that are selected to be published by the interfaces state broadcaster. This is published with transient local durability.
~/values (control_msgs::msg::Float64Values): The list of the values corresponding to the interface names that are selected to be published by the interfaces state broadcaster.
Note
The values are published at the same rate as the controller update rate.
Public Functions
-
StateInterfacesBroadcaster()
-
controller_interface::InterfaceConfiguration command_interface_configuration() const override
-
controller_interface::InterfaceConfiguration state_interface_configuration() const override
-
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
-
controller_interface::CallbackReturn on_init() override
-
controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
-
controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
Protected Attributes
-
std::shared_ptr<ParamListener> param_listener_
-
Params params_
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::Keys>> names_publisher_
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::Float64Values>> values_publisher_
-
std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::Float64Values>> realtime_values_publisher_
-
control_msgs::msg::Keys names_msg_
-
control_msgs::msg::Float64Values values_msg_