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 @@ -527,6 +527,18 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
527527 */
528528 const HardwareInfo & get_hardware_info () const { return info_; }
529529
530+ // / Prepare for the activation of the hardware.
531+ /* *
532+ * This method is called before the hardware is activated by the resource manager.
533+ */
534+ void prepare_for_activation ()
535+ {
536+ read_return_info_.store (return_type::OK, std::memory_order_release);
537+ read_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
538+ write_return_info_.store (return_type::OK, std::memory_order_release);
539+ write_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
540+ }
541+
530542 // / Enable or disable introspection of the hardware.
531543 /* *
532544 * \param[in] enable Enable introspection if true, disable otherwise.
Original file line number Diff line number Diff line change @@ -556,6 +556,18 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
556556 */
557557 const HardwareInfo & get_hardware_info () const { return info_; }
558558
559+ // / Prepare for the activation of the hardware.
560+ /* *
561+ * This method is called before the hardware is activated by the resource manager.
562+ */
563+ void prepare_for_activation ()
564+ {
565+ read_return_info_.store (return_type::OK, std::memory_order_release);
566+ read_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
567+ write_return_info_.store (return_type::OK, std::memory_order_release);
568+ write_execution_time_.store (std::chrono::nanoseconds::zero (), std::memory_order_release);
569+ }
570+
559571 // / Enable or disable introspection of the hardware.
560572 /* *
561573 * \param[in] enable Enable introspection if true, disable otherwise.
Original file line number Diff line number Diff line change @@ -147,6 +147,7 @@ const rclcpp_lifecycle::State & Actuator::activate()
147147 write_statistics_.reset_statistics ();
148148 if (impl_->get_lifecycle_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
149149 {
150+ impl_->prepare_for_activation ();
150151 switch (impl_->on_activate (impl_->get_lifecycle_state ()))
151152 {
152153 case CallbackReturn::SUCCESS:
Original file line number Diff line number Diff line change @@ -145,6 +145,7 @@ const rclcpp_lifecycle::State & System::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:
You can’t perform that action at this time.
0 commit comments