Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3237,7 +3237,6 @@ controller_interface::return_type ControllerManager::update(
}

PUBLISH_ROS2_CONTROL_INTROSPECTION_DATA_ASYNC(hardware_interface::DEFAULT_REGISTRY_KEY);
PUBLISH_ROS2_CONTROL_INTROSPECTION_DATA_ASYNC(hardware_interface::CM_STATISTICS_KEY);

execution_time_.update_time =
std::chrono::duration<double, std::micro>(std::chrono::steady_clock::now() - start_time)
Expand Down Expand Up @@ -3339,8 +3338,7 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
"Overrun might occur, Total time : %.3f us (Expected < %.3f us) --> Read time : %.3f us, "
"Update time : %.3f us (Switch time : %.3f us (Switch chained mode time : %.3f us, perform "
"mode change time : %.3f us, Activation time : %.3f us, Deactivation time : %.3f us)), "
"Write "
"time : %.3f us",
"Write time : %.3f us",
execution_time_.total_time, expected_cycle_time, execution_time_.read_time,
execution_time_.update_time, execution_time_.switch_time,
execution_time_.switch_chained_mode_time, execution_time_.switch_perform_mode_time,
Expand All @@ -3357,6 +3355,8 @@ void ControllerManager::write(const rclcpp::Time & time, const rclcpp::Duration
execution_time_.update_time, execution_time_.write_time);
}
}

PUBLISH_ROS2_CONTROL_INTROSPECTION_DATA_ASYNC(hardware_interface::CM_STATISTICS_KEY);
}

std::vector<ControllerSpec> &
Expand Down