71 controller_interface::return_type
update(
72 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
74 controller_interface::CallbackReturn
on_init()
override;
76 controller_interface::CallbackReturn on_configure(
77 const rclcpp_lifecycle::State & previous_state)
override;
79 controller_interface::CallbackReturn on_activate(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 controller_interface::CallbackReturn on_deactivate(
83 const rclcpp_lifecycle::State & previous_state)
override;
86 bool init_joint_data();
87 void init_auxiliary_data();
91 "use_all_available_interfaces is deprecated. Use use_urdf_joint_interfaces method instead")]]
92 bool use_all_available_interfaces()
const;
94 bool use_urdf_joint_interfaces()
const;
98 std::shared_ptr<ParamListener> param_listener_;
100 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
102 std::string frame_id_;
106 std::vector<std::string> joint_names_;
107 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
108 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
109 realtime_joint_state_publisher_;
110 sensor_msgs::msg::JointState joint_state_msg_;
112 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
115 bool is_model_loaded_ =
false;
117 std::vector<double *> mapped_values_;
121 JointStateData(
const double & position,
const double & velocity,
const double & effort)
122 : position_(position), velocity_(velocity), effort_(effort)
126 const double & position_;
127 const double & velocity_;
128 const double & effort_;
131 std::vector<JointStateData> joint_states_data_;