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();
89 void init_auxiliary_data();
91 void init_dynamic_joint_state_msg();
92 bool use_all_available_interfaces()
const;
96 std::shared_ptr<ParamListener> param_listener_;
98 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
100 std::string frame_id_;
104 std::vector<std::string> joint_names_;
105 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
106 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
107 realtime_joint_state_publisher_;
111 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
112 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
113 dynamic_joint_state_publisher_;
114 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
115 realtime_dynamic_joint_state_publisher_;
118 bool is_model_loaded_ =
false;
120 std::vector<double *> mapped_values_;
124 JointStateData(
const double & position,
const double & velocity,
const double & effort)
125 : position_(position), velocity_(velocity), effort_(effort)
129 const double & position_;
130 const double & velocity_;
131 const double & effort_;
134 std::vector<JointStateData> joint_states_data_;
136 std::vector<std::vector<const double *>> dynamic_joint_states_data_;