mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Plane: setup plane frame type parameter flags
This commit is contained in:
parent
4626b3a269
commit
0fc04b0158
@ -1335,5 +1335,7 @@ void Plane::load_parameters(void)
|
|||||||
AP_Param::set_default_by_name("SCHED_LOOP_RATE", 300);
|
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));
|
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||||
}
|
}
|
||||||
|
@ -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_6, SRV_Channel::k_motor2);
|
||||||
SRV_Channels::set_default_function(CH_8, SRV_Channel::k_motor4);
|
SRV_Channels::set_default_function(CH_8, SRV_Channel::k_motor4);
|
||||||
SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
|
SRV_Channels::set_default_function(CH_11, SRV_Channel::k_motor7);
|
||||||
|
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
|
||||||
break;
|
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());
|
||||||
|
Loading…
Reference in New Issue
Block a user