mirror of https://github.com/ArduPilot/ardupilot
Plane: removed separate tricopter quadplane build
can all be done with one build now
This commit is contained in:
parent
2a1408becf
commit
2f100b0804
|
@ -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_MOTORS_CLASS),
|
AP_SUBGROUPPTR(motors, "M_", 2, QuadPlane, AP_MotorsMulticopter),
|
||||||
|
|
||||||
// 3 ~ 8 were used by quadplane attitude control PIDs
|
// 3 ~ 8 were used by quadplane attitude control PIDs
|
||||||
|
|
||||||
|
@ -369,7 +369,8 @@ bool QuadPlane::setup(void)
|
||||||
}
|
}
|
||||||
float loop_delta_t = 1.0 / plane.scheduler.get_loop_rate_hz();
|
float loop_delta_t = 1.0 / plane.scheduler.get_loop_rate_hz();
|
||||||
|
|
||||||
#if FRAME_CONFIG != TRI_FRAME
|
enum AP_Motors::motor_frame_class motor_class;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
cope with upgrade from old AP_Motors values for frame_class
|
cope with upgrade from old AP_Motors values for frame_class
|
||||||
*/
|
*/
|
||||||
|
@ -397,7 +398,6 @@ bool QuadPlane::setup(void)
|
||||||
}
|
}
|
||||||
frame_class.set_and_save(new_value);
|
frame_class.set_and_save(new_value);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (hal.util->available_memory() <
|
if (hal.util->available_memory() <
|
||||||
4096 + sizeof(*motors) + sizeof(*attitude_control) + sizeof(*pos_control) + sizeof(*wp_nav)) {
|
4096 + sizeof(*motors) + sizeof(*attitude_control) + sizeof(*pos_control) + sizeof(*wp_nav)) {
|
||||||
|
@ -405,20 +405,13 @@ bool QuadPlane::setup(void)
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if FRAME_CONFIG == TRI_FRAME
|
|
||||||
SRV_Channels::set_default_function(CH_5, SRV_Channel::k_motor1);
|
|
||||||
SRV_Channels::set_default_function(CH_6, SRV_Channel::k_motor2);
|
|
||||||
SRV_Channels::set_default_function(CH_8, SRV_Channel::k_motor4);
|
|
||||||
SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
|
|
||||||
frame_class.set(AP_Motors::MOTOR_FRAME_TRI);
|
|
||||||
motors = new AP_MOTORS_CLASS(plane.scheduler.get_loop_rate_hz());
|
|
||||||
#else
|
|
||||||
/*
|
/*
|
||||||
dynamically allocate the key objects for quadplane. This ensures
|
dynamically allocate the key objects for quadplane. This ensures
|
||||||
that the objects don't affect the vehicle unless enabled and
|
that the objects don't affect the vehicle unless enabled and
|
||||||
also saves memory when not in use
|
also saves memory when not in use
|
||||||
*/
|
*/
|
||||||
switch ((enum AP_Motors::motor_frame_class)frame_class.get()) {
|
motor_class = (enum AP_Motors::motor_frame_class)frame_class.get();
|
||||||
|
switch (motor_class) {
|
||||||
case AP_Motors::MOTOR_FRAME_QUAD:
|
case AP_Motors::MOTOR_FRAME_QUAD:
|
||||||
setup_default_channels(4);
|
setup_default_channels(4);
|
||||||
break;
|
break;
|
||||||
|
@ -432,12 +425,21 @@ bool QuadPlane::setup(void)
|
||||||
case AP_Motors::MOTOR_FRAME_Y6:
|
case AP_Motors::MOTOR_FRAME_Y6:
|
||||||
setup_default_channels(7);
|
setup_default_channels(7);
|
||||||
break;
|
break;
|
||||||
|
case AP_Motors::MOTOR_FRAME_TRI:
|
||||||
|
SRV_Channels::set_default_function(CH_5, SRV_Channel::k_motor1);
|
||||||
|
SRV_Channels::set_default_function(CH_6, SRV_Channel::k_motor2);
|
||||||
|
SRV_Channels::set_default_function(CH_8, SRV_Channel::k_motor4);
|
||||||
|
SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get());
|
hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get());
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz());
|
if (motor_class == AP_Motors::MOTOR_FRAME_TRI) {
|
||||||
#endif // AP_MOTORS_CLASS
|
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz());
|
||||||
|
} else {
|
||||||
|
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz());
|
||||||
|
}
|
||||||
const static char *strUnableToAllocate = "Unable to allocate";
|
const static char *strUnableToAllocate = "Unable to allocate";
|
||||||
if (!motors) {
|
if (!motors) {
|
||||||
hal.console->printf("%s motors\n", strUnableToAllocate);
|
hal.console->printf("%s motors\n", strUnableToAllocate);
|
||||||
|
|
|
@ -8,24 +8,6 @@
|
||||||
#include <AC_Avoidance/AC_Avoid.h>
|
#include <AC_Avoidance/AC_Avoid.h>
|
||||||
#include <AP_Proximity/AP_Proximity.h>
|
#include <AP_Proximity/AP_Proximity.h>
|
||||||
|
|
||||||
/*
|
|
||||||
frame types for quadplane build. Most case be set with
|
|
||||||
parameters. Those that can't are listed here and chosen with a build
|
|
||||||
time FRAME_CONFIG parameter
|
|
||||||
*/
|
|
||||||
#define MULTICOPTER_FRAME 1
|
|
||||||
#define TRI_FRAME 2
|
|
||||||
|
|
||||||
#ifndef FRAME_CONFIG
|
|
||||||
# define FRAME_CONFIG MULTICOPTER_FRAME
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if FRAME_CONFIG == TRI_FRAME
|
|
||||||
#define AP_MOTORS_CLASS AP_MotorsTri
|
|
||||||
#else
|
|
||||||
#define AP_MOTORS_CLASS AP_MotorsMulticopter
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
QuadPlane specific functionality
|
QuadPlane specific functionality
|
||||||
*/
|
*/
|
||||||
|
@ -124,7 +106,7 @@ private:
|
||||||
AP_Int8 frame_class;
|
AP_Int8 frame_class;
|
||||||
AP_Int8 frame_type;
|
AP_Int8 frame_type;
|
||||||
|
|
||||||
AP_MOTORS_CLASS *motors;
|
AP_MotorsMulticopter *motors;
|
||||||
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;
|
||||||
|
|
|
@ -41,10 +41,3 @@ def build(bld):
|
||||||
program_groups=['bin', 'plane'],
|
program_groups=['bin', 'plane'],
|
||||||
use=vehicle + '_libs',
|
use=vehicle + '_libs',
|
||||||
)
|
)
|
||||||
|
|
||||||
bld.ap_program(
|
|
||||||
program_name='arduplane-tri',
|
|
||||||
program_groups=['bin', 'plane'],
|
|
||||||
use=vehicle + '_libs',
|
|
||||||
defines=['FRAME_CONFIG=TRI_FRAME'],
|
|
||||||
)
|
|
||||||
|
|
Loading…
Reference in New Issue