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
526
526
*/
527
527
const HardwareInfo & get_hardware_info () const { return info_; }
528
528
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
+
529
541
protected:
530
542
HardwareInfo info_;
531
543
// 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
555
555
*/
556
556
const HardwareInfo & get_hardware_info () const { return info_; }
557
557
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
+
558
570
protected:
559
571
HardwareInfo info_;
560
572
// interface names to InterfaceDescription
Original file line number Diff line number Diff line change @@ -145,6 +145,7 @@ const rclcpp_lifecycle::State & Actuator::activate()
145
145
write_statistics_.reset_statistics ();
146
146
if (impl_->get_lifecycle_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
147
147
{
148
+ impl_->prepare_for_activation ();
148
149
switch (impl_->on_activate (impl_->get_lifecycle_state ()))
149
150
{
150
151
case CallbackReturn::SUCCESS:
Original file line number Diff line number Diff line change @@ -143,6 +143,7 @@ const rclcpp_lifecycle::State & System::activate()
143
143
write_statistics_.reset_statistics ();
144
144
if (impl_->get_lifecycle_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
145
145
{
146
+ impl_->prepare_for_activation ();
146
147
switch (impl_->on_activate (impl_->get_lifecycle_state ()))
147
148
{
148
149
case CallbackReturn::SUCCESS:
You can’t perform that action at this time.
0 commit comments