diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index b1212c7b51..0569e21695 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1335,5 +1335,7 @@ void Plane::load_parameters(void) AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300); } + AP_Param::set_frame_type_flags(AP_PARAM_FRAME_PLANE); + cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before)); } diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 00c593dd1d..c6f7adbd38 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -437,6 +437,7 @@ bool QuadPlane::setup(void) 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); + AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER); break; default: hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get());