diff --git a/src/comm/px4_custom_mode.h b/src/comm/px4_custom_mode.h index 9c0c8ae91ea11ffbcd6e1d101da32c12ab207174..a0fed6a277e931ef3b7c4b7300565c2214641fb7 100644 --- a/src/comm/px4_custom_mode.h +++ b/src/comm/px4_custom_mode.h @@ -3,8 +3,8 @@ enum PX4_CUSTOM_MAIN_MODE { PX4_CUSTOM_MAIN_MODE_MANUAL = 1, - PX4_CUSTOM_MAIN_MODE_SEATBELT, - PX4_CUSTOM_MAIN_MODE_EASY, + PX4_CUSTOM_MAIN_MODE_ALTCTL, + PX4_CUSTOM_MAIN_MODE_POSCTL, PX4_CUSTOM_MAIN_MODE_AUTO, }; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 98ec5d79d65e370aa83b1a244be910ceb40ba44f..c576a471fada70d70b00a2392bc789ef7a819601 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -3394,10 +3394,10 @@ QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode, int au px4_mode.data = custom_mode; if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) { mode += "|MANUAL"; - } else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) { - mode += "|SEATBELT"; - } else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_EASY) { - mode += "|EASY"; + } else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) { + mode += "|ALTCTL"; + } else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) { + mode += "|POSCTL"; } else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) { mode += "|AUTO"; if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_READY) { diff --git a/src/ui/uas/UASControlWidget.cc b/src/ui/uas/UASControlWidget.cc index bf26d918bea7978272f55b870e0db99e6e0e12c9..d8ccfd48b8b5e8f462db35bf86878777f6a7aa76 100644 --- a/src/ui/uas/UASControlWidget.cc +++ b/src/ui/uas/UASControlWidget.cc @@ -80,10 +80,10 @@ void UASControlWidget::updateModesList() px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL; modes_list_px4[0].customMode = px4_cm.data; modes_list_px4[1].baseMode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED; - px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT; + px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL; modes_list_px4[1].customMode = px4_cm.data; modes_list_px4[2].baseMode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED; - px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_EASY; + px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL; modes_list_px4[2].customMode = px4_cm.data; modes_list_px4[3].baseMode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED; px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;