mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: force cam pan and tilt inputs to channels 7 and 8
This commit is contained in:
parent
8b92df51db
commit
db6beb913d
@ -701,6 +701,8 @@ void Sub::load_parameters()
|
||||
AP_Param::set_default_by_name("INS_GYR_CAL", 0);
|
||||
AP_Param::set_default_by_name("MNT_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING);
|
||||
AP_Param::set_default_by_name("MNT_JSTICK_SPD", 100);
|
||||
AP_Param::set_by_name("MNT_RC_IN_PAN", 7);
|
||||
AP_Param::set_by_name("MNT_RC_IN_TILT", 8);
|
||||
}
|
||||
|
||||
void Sub::convert_old_parameters()
|
||||
|
Loading…
Reference in New Issue
Block a user