74 controller_interface::return_type
update(
75 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
77 controller_interface::CallbackReturn
on_init()
override;
79 controller_interface::CallbackReturn on_configure(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 controller_interface::CallbackReturn on_activate(
83 const rclcpp_lifecycle::State & previous_state)
override;
85 controller_interface::CallbackReturn on_deactivate(
86 const rclcpp_lifecycle::State & previous_state)
override;
89 bool init_joint_data();
90 void init_auxiliary_data();
92 void init_dynamic_joint_state_msg();
93 bool use_all_available_interfaces()
const;
97 std::shared_ptr<ParamListener> param_listener_;
99 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
101 std::string frame_id_;
105 std::vector<std::string> joint_names_;
106 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
107 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
108 realtime_joint_state_publisher_;
109 sensor_msgs::msg::JointState joint_state_msg_;
113 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
114 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
115 dynamic_joint_state_publisher_;
116 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
117 realtime_dynamic_joint_state_publisher_;
118 control_msgs::msg::DynamicJointState dynamic_joint_state_msg_;
121 bool is_model_loaded_ =
false;
123 std::vector<double *> mapped_values_;
127 JointStateData(
const double & position,
const double & velocity,
const double & effort)
128 : position_(position), velocity_(velocity), effort_(effort)
132 const double & position_;
133 const double & velocity_;
134 const double & effort_;
137 std::vector<JointStateData> joint_states_data_;
139 std::vector<std::vector<const double *>> dynamic_joint_states_data_;