73 controller_interface::return_type
update(
74 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
76 controller_interface::CallbackReturn
on_init()
override;
78 controller_interface::CallbackReturn on_configure(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 controller_interface::CallbackReturn on_activate(
82 const rclcpp_lifecycle::State & previous_state)
override;
84 controller_interface::CallbackReturn on_deactivate(
85 const rclcpp_lifecycle::State & previous_state)
override;
88 bool init_joint_data();
90 void init_dynamic_joint_state_msg();
91 bool use_all_available_interfaces()
const;
95 std::shared_ptr<ParamListener> param_listener_;
97 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
101 std::vector<std::string> joint_names_;
102 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
103 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
104 realtime_joint_state_publisher_;
108 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
109 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
110 dynamic_joint_state_publisher_;
111 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
112 realtime_dynamic_joint_state_publisher_;
115 bool is_model_loaded_ =
false;