mirror of https://github.com/ArduPilot/ardupilot
SITL: move to 32 servo outs
This commit is contained in:
parent
6921763b02
commit
572ebf29da
|
@ -7,7 +7,7 @@
|
||||||
microseconds
|
microseconds
|
||||||
*/
|
*/
|
||||||
struct sitl_input {
|
struct sitl_input {
|
||||||
uint16_t servos[16];
|
uint16_t servos[32];
|
||||||
struct {
|
struct {
|
||||||
float speed; // m/s
|
float speed; // m/s
|
||||||
float direction; // degrees 0..360
|
float direction; // degrees 0..360
|
||||||
|
|
Loading…
Reference in New Issue