File tree Expand file tree Collapse file tree 4 files changed +26
-0
lines changed
include/hardware_interface Expand file tree Collapse file tree 4 files changed +26
-0
lines changed Original file line number Diff line number Diff line change @@ -526,6 +526,18 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
526526 */
527527 const HardwareInfo & get_hardware_info () const { return info_; }
528528
529+ // / Prepare for the activation of the hardware.
530+ /* *
531+ * This method is called before the hardware is activated by the resource manager.
532+ */
533+ void prepare_for_activation ()
534+ {
535+ read_return_info_.store (return_type::OK, std::memory_order_release);
536+ read_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
537+ write_return_info_.store (return_type::OK, std::memory_order_release);
538+ write_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
539+ }
540+
529541protected:
530542 HardwareInfo info_;
531543 // interface names to InterfaceDescription
Original file line number Diff line number Diff line change @@ -555,6 +555,18 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
555555 */
556556 const HardwareInfo & get_hardware_info () const { return info_; }
557557
558+ // / Prepare for the activation of the hardware.
559+ /* *
560+ * This method is called before the hardware is activated by the resource manager.
561+ */
562+ void prepare_for_activation ()
563+ {
564+ read_return_info_.store (return_type::OK, std::memory_order_release);
565+ read_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
566+ write_return_info_.store (return_type::OK, std::memory_order_release);
567+ write_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
568+ }
569+
558570protected:
559571 HardwareInfo info_;
560572 // interface names to InterfaceDescription
Original file line number Diff line number Diff line change @@ -145,6 +145,7 @@ const rclcpp_lifecycle::State & Actuator::activate()
145145 write_statistics_.reset_statistics ();
146146 if (impl_->get_lifecycle_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
147147 {
148+ impl_->prepare_for_activation ();
148149 switch (impl_->on_activate (impl_->get_lifecycle_state ()))
149150 {
150151 case CallbackReturn::SUCCESS:
Original file line number Diff line number Diff line change @@ -143,6 +143,7 @@ const rclcpp_lifecycle::State & System::activate()
143143 write_statistics_.reset_statistics ();
144144 if (impl_->get_lifecycle_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
145145 {
146+ impl_->prepare_for_activation ();
146147 switch (impl_->on_activate (impl_->get_lifecycle_state ()))
147148 {
148149 case CallbackReturn::SUCCESS:
You can’t perform that action at this time.
0 commit comments