|
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 |
|
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 |
|
bool | is_chainable () const final |
|
std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
|
std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
|
bool | set_chained_mode (bool chained_mode) final |
|
bool | is_in_chained_mode () const final |
|
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) |
|
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) |
|
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 |
|
unsigned int | get_update_rate () const |
|
bool | is_async () const |
|
const std::string & | get_robot_description () const |
|
virtual rclcpp::NodeOptions | define_custom_node_options () const |
|
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 () |
|
void | prepare_for_deactivation () |
|
std::string | get_name () const |
|
void | enable_introspection (bool enable) |
| Enable or disable introspection of the controller.
|
|
|
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_ |
|
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_ |
|
urdf::Model | model_ |
|
bool | is_model_loaded_ = false |
|
std::vector< double * > | mapped_values_ |
|
std::vector< JointStateData > | joint_states_data_ |
|
std::vector< std::vector< const double * > > | dynamic_joint_states_data_ |
|
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
|
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
|
pal_statistics::RegistrationsRAII | stats_registrations_ |
|
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.