Skip to content

Commit

Permalink
Rename the variable ok to successful and add documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Dec 3, 2024
1 parent de5d617 commit 18e67f6
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,19 @@ struct ControllerUpdateStats
unsigned int failed_triggers;
};

/**
* Struct to store the status of the controller update method.
* The status contains information if the update was triggered successfully, the result of the
* update method and the execution duration of the update method. The status is used to provide
* feedback to the controller_manager.
* @var successful: true if the update was triggered successfully, false if not.
* @var result: return_type::OK if update is successfully, otherwise return_type::ERROR.
* @var execution_time: duration of the execution of the update method.
* @var period: period of the update method.
*/
struct ControllerUpdateStatus
{
bool ok = true;
bool successful = true;
return_type result = return_type::OK;
std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
std::optional<rclcpp::Duration> period = std::nullopt;
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ ControllerUpdateStatus ControllerInterfaceBase::trigger_update(
"The controller missed %u update cycles out of %u total triggers.",
trigger_stats_.failed_triggers, trigger_stats_.total_triggers);
}
status.ok = result.first;
status.successful = result.first;
status.result = result.second;
const auto execution_time = async_handler_->get_last_execution_time();
if (execution_time.count() > 0)
Expand All @@ -191,7 +191,7 @@ ControllerUpdateStatus ControllerInterfaceBase::trigger_update(
else
{
const auto start_time = std::chrono::steady_clock::now();
status.ok = true;
status.successful = true;
status.result = update(time, period);
status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::steady_clock::now() - start_time);
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2432,7 +2432,7 @@ controller_interface::return_type ControllerManager::update(
{
const auto trigger_result =
loaded_controller.c->trigger_update(current_time, controller_actual_period);
trigger_status = trigger_result.ok;
trigger_status = trigger_result.successful;
controller_ret = trigger_result.result;
if (trigger_status && trigger_result.execution_time.has_value())
{
Expand Down

0 comments on commit 18e67f6

Please sign in to comment.