mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_Motors: allow arbitrary motor mapping with tricopters
This commit is contained in:
parent
4908350ccb
commit
ff96085bd3
@ -82,6 +82,10 @@ const AP_Param::GroupInfo AP_MotorsTri::var_info[] = {
|
|||||||
// init
|
// init
|
||||||
void AP_MotorsTri::Init()
|
void AP_MotorsTri::Init()
|
||||||
{
|
{
|
||||||
|
add_motor_num(AP_MOTORS_MOT_1);
|
||||||
|
add_motor_num(AP_MOTORS_MOT_2);
|
||||||
|
add_motor_num(AP_MOTORS_MOT_4);
|
||||||
|
|
||||||
// set update rate for the 3 motors (but not the servo on channel 7)
|
// set update rate for the 3 motors (but not the servo on channel 7)
|
||||||
set_update_rate(_speed_hz);
|
set_update_rate(_speed_hz);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user