mirror of https://github.com/ArduPilot/ardupilot
Blimp: fixup mavlink mav type, fix mode ordering
This commit is contained in:
parent
b77580f934
commit
0ee8b452ab
|
@ -27,12 +27,12 @@ Mode *Blimp::mode_from_mode_num(const Mode::Number mode)
|
|||
Mode *ret = nullptr;
|
||||
|
||||
switch (mode) {
|
||||
case Mode::Number::MANUAL:
|
||||
ret = &mode_manual;
|
||||
break;
|
||||
case Mode::Number::LAND:
|
||||
ret = &mode_land;
|
||||
break;
|
||||
case Mode::Number::MANUAL:
|
||||
ret = &mode_manual;
|
||||
break;
|
||||
case Mode::Number::VELOCITY:
|
||||
ret = &mode_velocity;
|
||||
break;
|
||||
|
|
|
@ -13,8 +13,8 @@ public:
|
|||
|
||||
// Auto Pilot Modes enumeration
|
||||
enum class Number : uint8_t {
|
||||
MANUAL = 0, // manual control
|
||||
LAND = 1, // currently just stops moving
|
||||
LAND = 0, // currently just stops moving
|
||||
MANUAL = 1, // manual control
|
||||
VELOCITY = 2, // velocity mode
|
||||
LOITER = 3, // loiter mode (position hold)
|
||||
};
|
||||
|
|
|
@ -241,7 +241,7 @@ bool Blimp::should_log(uint32_t mask)
|
|||
// return MAV_TYPE corresponding to frame class
|
||||
MAV_TYPE Blimp::get_frame_mav_type()
|
||||
{
|
||||
return MAV_TYPE_QUADROTOR; //TODO: Mavlink changes to allow type to be correct
|
||||
return MAV_TYPE_AIRSHIP;
|
||||
}
|
||||
|
||||
// return string corresponding to frame_class
|
||||
|
|
Loading…
Reference in New Issue