Skip to content

Commit

Permalink
Rover: Determine the prearm check results
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed May 12, 2024
1 parent c3c6d7f commit 9cc366f
Showing 1 changed file with 8 additions and 6 deletions.
14 changes: 8 additions & 6 deletions Rover/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,12 +212,14 @@ bool AP_Arming_Rover::motor_checks(bool report)
bool ret = rover.g2.motors.pre_arm_check(report);

#if HAL_TORQEEDO_ENABLED
char failure_msg[50] = {};
AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();
if (torqeedo != nullptr) {
if (!torqeedo->pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {
check_failed(report, "Torqeedo: %s", failure_msg);
ret = false;
if (ret) {
char failure_msg[50] = {};
AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();
if (torqeedo != nullptr) {
if (!torqeedo->pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {
check_failed(report, "Torqeedo: %s", failure_msg);
ret = false;
}
}
}
#endif
Expand Down

0 comments on commit 9cc366f

Please sign in to comment.