mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: changes for AC_WPNav
This commit is contained in:
parent
17e1329068
commit
f1917dddd0
@ -607,13 +607,13 @@ void Copter::allocate_motors(void)
|
|||||||
}
|
}
|
||||||
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);
|
AP_Param::load_object_from_eeprom(pos_control, pos_control->var_info);
|
||||||
|
|
||||||
wp_nav = new AC_WPNav(inertial_nav, ahrs, *pos_control, *attitude_control);
|
wp_nav = new AC_WPNav(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
|
||||||
if (wp_nav == nullptr) {
|
if (wp_nav == nullptr) {
|
||||||
AP_HAL::panic("Unable to allocate WPNav");
|
AP_HAL::panic("Unable to allocate WPNav");
|
||||||
}
|
}
|
||||||
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
|
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
|
||||||
|
|
||||||
circle_nav = new AC_Circle(inertial_nav, ahrs, *pos_control);
|
circle_nav = new AC_Circle(inertial_nav, *ahrs_view, *pos_control);
|
||||||
if (wp_nav == nullptr) {
|
if (wp_nav == nullptr) {
|
||||||
AP_HAL::panic("Unable to allocate CircleNav");
|
AP_HAL::panic("Unable to allocate CircleNav");
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user