1919#include < map>
2020#include < memory>
2121#include < string>
22+ #include < unordered_map>
2223#include < utility>
2324#include < vector>
2425
@@ -136,20 +137,18 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
136137
137138 // / Exports all state interfaces for this hardware interface.
138139 /* *
139- * Default implementation for exporting the StateInterfaces. The StateInterfaces are created
140- * according to the InterfaceDescription. The memory accessed by the controllers and hardware is
141- * assigned here and resides in the system_interface.
142- *
143- * If overwritten:
144- * The state interfaces have to be created and transferred according
145- * to the hardware info passed in for the configuration.
140+ * Old way of exporting the StateInterfaces. If a empty vector is returned then
141+ * the on_export_state_interfaces() method is called. If a vector with StateInterfaces is returned
142+ * then the exporting of the StateInterfaces is only done with this function and the ownership is
143+ * transferred to the resource manager. The set_command(...), get_command(...), ..., can then not
144+ * be used.
146145 *
147146 * Note the ownership over the state interfaces is transferred to the caller.
148147 *
149148 * \return vector of state interfaces
150149 */
151150 [[deprecated(
152- " Replaced by vector<std::shared_ptr<StateInterface> > on_export_state_interfaces() method. "
151+ " Replaced by vector<StateInterfaceSharedPtr > on_export_state_interfaces() method. "
153152 " Exporting is "
154153 " handled "
155154 " by the Framework." )]] virtual std::vector<StateInterface>
@@ -160,33 +159,41 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
160159 return {};
161160 }
162161
163- std::vector<std::shared_ptr<StateInterface>> on_export_state_interfaces ()
162+ /* *
163+ * Default implementation for exporting the StateInterfaces. The StateInterfaces are created
164+ * according to the InterfaceDescription. The memory accessed by the controllers and hardware is
165+ * assigned here and resides in the actuator_interface.
166+ *
167+ * \return vector of shared pointers to the created and stored StateInterfaces
168+ */
169+ virtual std::vector<StateInterfaceSharedPtr> on_export_state_interfaces ()
164170 {
165- std::vector<std::shared_ptr<StateInterface> > state_interfaces;
171+ std::vector<StateInterfaceSharedPtr > state_interfaces;
166172 state_interfaces.reserve (joint_state_interfaces_.size ());
167173
168174 for (const auto & [name, descr] : joint_state_interfaces_)
169175 {
170- actuator_states_.insert (std::make_pair (name, std::make_shared<StateInterface>(descr)));
171- state_interfaces.push_back (actuator_states_.at (name));
176+ auto state_interface = std::make_shared<StateInterface>(descr);
177+ actuator_states_.insert (std::make_pair (name, state_interface));
178+ state_interfaces.push_back (state_interface);
172179 }
173180 return state_interfaces;
174181 }
182+
175183 // / Exports all command interfaces for this hardware interface.
176184 /* *
177- * Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created
178- * according to the InterfaceDescription. The memory accessed by the controllers and hardware is
179- * assigned here and resides in the system_interface.
180- *
181- * The command interfaces have to be created and transferred according
182- * to the hardware info passed in for the configuration.
185+ * Old way of exporting the CommandInterfaces. If a empty vector is returned then
186+ * the on_export_command_interfaces() method is called. If a vector with CommandInterfaces is
187+ * returned then the exporting of the CommandInterfaces is only done with this function and the
188+ * ownership is transferred to the resource manager. The set_command(...), get_command(...), ...,
189+ * can then not be used.
183190 *
184191 * Note the ownership over the state interfaces is transferred to the caller.
185192 *
186- * \return vector of command interfaces
193+ * \return vector of state interfaces
187194 */
188195 [[deprecated(
189- " Replaced by vector<std::shared_ptr<CommandInterface> > on_export_command_interfaces() method. "
196+ " Replaced by vector<CommandInterfaceSharedPtr > on_export_command_interfaces() method. "
190197 " Exporting is "
191198 " handled "
192199 " by the Framework." )]] virtual std::vector<CommandInterface>
@@ -197,15 +204,23 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
197204 return {};
198205 }
199206
200- std::vector<std::shared_ptr<CommandInterface>> on_export_command_interfaces ()
207+ /* *
208+ * Default implementation for exporting the CommandInterfaces. The CommandInterfaces are created
209+ * according to the InterfaceDescription. The memory accessed by the controllers and hardware is
210+ * assigned here and resides in the actuator_interface.
211+ *
212+ * \return vector of shared pointers to the created and stored CommandInterfaces
213+ */
214+ virtual std::vector<CommandInterfaceSharedPtr> on_export_command_interfaces ()
201215 {
202- std::vector<std::shared_ptr<CommandInterface> > command_interfaces;
216+ std::vector<CommandInterfaceSharedPtr > command_interfaces;
203217 command_interfaces.reserve (joint_command_interfaces_.size ());
204218
205219 for (const auto & [name, descr] : joint_command_interfaces_)
206220 {
207- actuator_commands_.insert (std::make_pair (name, std::make_shared<CommandInterface>(descr)));
208- command_interfaces.push_back (actuator_commands_.at (name));
221+ auto command_interface = std::make_shared<CommandInterface>(descr);
222+ actuator_commands_.insert (std::make_pair (name, command_interface));
223+ command_interfaces.push_back (command_interface);
209224 }
210225
211226 return command_interfaces;
@@ -315,9 +330,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
315330 std::map<std::string, InterfaceDescription> joint_state_interfaces_;
316331 std::map<std::string, InterfaceDescription> joint_command_interfaces_;
317332
318- private:
319- std::map<std::string, std::shared_ptr<StateInterface>> actuator_states_;
320- std::map<std::string, std::shared_ptr<CommandInterface>> actuator_commands_;
333+ std::unordered_map<std::string, StateInterfaceSharedPtr> actuator_states_;
334+ std::unordered_map<std::string, CommandInterfaceSharedPtr> actuator_commands_;
321335
322336 rclcpp_lifecycle::State lifecycle_state_;
323337};
0 commit comments