Change default vehicle type to fixedwing.

This commit is contained in:
James Goppert 2013-01-13 17:35:56 -05:00
parent 464c5245f2
commit a40f41d216

View File

@ -77,7 +77,7 @@
/* define MAVLink specific parameters */
PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_QUADROTOR);
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
__EXPORT int mavlink_main(int argc, char *argv[]);
@ -98,7 +98,7 @@ static bool mavlink_link_termination_allowed = false;
mavlink_system_t mavlink_system = {
100,
50,
MAV_TYPE_QUADROTOR,
MAV_TYPE_FIXED_WING,
0,
0,
0