mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Plane: make the quadplane motors var_info dynamic
this will allow for more quadplane motors class types
This commit is contained in:
parent
47803e73e4
commit
5d06e4238f
@ -11,7 +11,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
|
|
||||||
// @Group: M_
|
// @Group: M_
|
||||||
// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
|
// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
|
||||||
AP_SUBGROUPPTR(motors, "M_", 2, QuadPlane, AP_MotorsMulticopter),
|
AP_SUBGROUPVARPTR(motors, "M_", 2, QuadPlane, plane.quadplane.motors_var_info),
|
||||||
|
|
||||||
// 3 ~ 8 were used by quadplane attitude control PIDs
|
// 3 ~ 8 were used by quadplane attitude control PIDs
|
||||||
|
|
||||||
@ -482,20 +482,19 @@ bool QuadPlane::setup(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
const struct AP_Param::GroupInfo *var_info;
|
|
||||||
switch (motor_class) {
|
switch (motor_class) {
|
||||||
case AP_Motors::MOTOR_FRAME_TRI:
|
case AP_Motors::MOTOR_FRAME_TRI:
|
||||||
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz());
|
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz());
|
||||||
var_info = AP_MotorsTri::var_info;
|
motors_var_info = AP_MotorsTri::var_info;
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
||||||
motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz());
|
motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz());
|
||||||
var_info = AP_MotorsTailsitter::var_info;
|
motors_var_info = AP_MotorsTailsitter::var_info;
|
||||||
rotation = ROTATION_PITCH_90;
|
rotation = ROTATION_PITCH_90;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz());
|
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz());
|
||||||
var_info = AP_MotorsMatrix::var_info;
|
motors_var_info = AP_MotorsMatrix::var_info;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
const static char *strUnableToAllocate = "Unable to allocate";
|
const static char *strUnableToAllocate = "Unable to allocate";
|
||||||
@ -504,7 +503,7 @@ bool QuadPlane::setup(void)
|
|||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Param::load_object_from_eeprom(motors, var_info);
|
AP_Param::load_object_from_eeprom(motors, motors_var_info);
|
||||||
|
|
||||||
// create the attitude view used by the VTOL code
|
// create the attitude view used by the VTOL code
|
||||||
ahrs_view = ahrs.create_view(rotation);
|
ahrs_view = ahrs.create_view(rotation);
|
||||||
|
@ -122,6 +122,8 @@ private:
|
|||||||
AP_Int8 frame_type;
|
AP_Int8 frame_type;
|
||||||
|
|
||||||
AP_MotorsMulticopter *motors;
|
AP_MotorsMulticopter *motors;
|
||||||
|
const struct AP_Param::GroupInfo *motors_var_info;
|
||||||
|
|
||||||
AC_AttitudeControl_Multi *attitude_control;
|
AC_AttitudeControl_Multi *attitude_control;
|
||||||
AC_PosControl *pos_control;
|
AC_PosControl *pos_control;
|
||||||
AC_WPNav *wp_nav;
|
AC_WPNav *wp_nav;
|
||||||
|
Loading…
Reference in New Issue
Block a user