Copter: Move to the processing section to be used

This commit is contained in:
muramura 2024-06-16 10:23:03 +09:00 committed by Randy Mackay
parent a737a34cd0
commit 9135f01a93
1 changed files with 1 additions and 2 deletions

View File

@ -22,8 +22,6 @@ bool ModeCircle::init(bool ignore_checks)
copter.circle_nav->init();
#if HAL_MOUNT_ENABLED
AP_Mount *s = AP_Mount::get_singleton();
// Check if the CIRCLE_OPTIONS parameter have roi_at_center
if (copter.circle_nav->roi_at_center()) {
const Vector3p &pos { copter.circle_nav->get_center() };
@ -33,6 +31,7 @@ bool ModeCircle::init(bool ignore_checks)
}
// point at the ground:
circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN);
AP_Mount *s = AP_Mount::get_singleton();
s->set_roi_target(circle_center);
}
#endif