mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: remove learning mode
saving waypoints can be done in manual or steering mode
This commit is contained in:
parent
524fe4cd82
commit
14c74a5967
@ -815,7 +815,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
case MAV_MODE_STABILIZE_DISARMED:
|
case MAV_MODE_STABILIZE_DISARMED:
|
||||||
case MAV_MODE_STABILIZE_ARMED:
|
case MAV_MODE_STABILIZE_ARMED:
|
||||||
rover.set_mode(rover.mode_learning, MODE_REASON_GCS_COMMAND);
|
rover.set_mode(rover.mode_steering, MODE_REASON_GCS_COMMAND);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -241,45 +241,45 @@ const AP_Param::Info Rover::var_info[] = {
|
|||||||
|
|
||||||
// @Param: MODE1
|
// @Param: MODE1
|
||||||
// @DisplayName: Mode1
|
// @DisplayName: Mode1
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
|
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
|
||||||
GSCALAR(mode1, "MODE1", MODE_1),
|
GSCALAR(mode1, "MODE1", MANUAL),
|
||||||
|
|
||||||
// @Param: MODE2
|
// @Param: MODE2
|
||||||
// @DisplayName: Mode2
|
// @DisplayName: Mode2
|
||||||
// @Description: Driving mode for switch position 2 (1231 to 1360)
|
// @Description: Driving mode for switch position 2 (1231 to 1360)
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode2, "MODE2", MODE_2),
|
GSCALAR(mode2, "MODE2", MANUAL),
|
||||||
|
|
||||||
// @Param: MODE3
|
// @Param: MODE3
|
||||||
// @DisplayName: Mode3
|
// @DisplayName: Mode3
|
||||||
// @Description: Driving mode for switch position 3 (1361 to 1490)
|
// @Description: Driving mode for switch position 3 (1361 to 1490)
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode3, "MODE3", MODE_3),
|
GSCALAR(mode3, "MODE3", MANUAL),
|
||||||
|
|
||||||
// @Param: MODE4
|
// @Param: MODE4
|
||||||
// @DisplayName: Mode4
|
// @DisplayName: Mode4
|
||||||
// @Description: Driving mode for switch position 4 (1491 to 1620)
|
// @Description: Driving mode for switch position 4 (1491 to 1620)
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode4, "MODE4", MODE_4),
|
GSCALAR(mode4, "MODE4", MANUAL),
|
||||||
|
|
||||||
// @Param: MODE5
|
// @Param: MODE5
|
||||||
// @DisplayName: Mode5
|
// @DisplayName: Mode5
|
||||||
// @Description: Driving mode for switch position 5 (1621 to 1749)
|
// @Description: Driving mode for switch position 5 (1621 to 1749)
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode5, "MODE5", MODE_5),
|
GSCALAR(mode5, "MODE5", MANUAL),
|
||||||
|
|
||||||
// @Param: MODE6
|
// @Param: MODE6
|
||||||
// @DisplayName: Mode6
|
// @DisplayName: Mode6
|
||||||
// @Description: Driving mode for switch position 6 (1750 to 2049)
|
// @Description: Driving mode for switch position 6 (1750 to 2049)
|
||||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
// @Values: 0:Manual,3:Steering,4:Hold,10:Auto,11:RTL,15:Guided
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode6, "MODE6", MODE_6),
|
GSCALAR(mode6, "MODE6", MANUAL),
|
||||||
|
|
||||||
// @Param: WP_RADIUS
|
// @Param: WP_RADIUS
|
||||||
// @DisplayName: Waypoint radius
|
// @DisplayName: Waypoint radius
|
||||||
|
@ -160,7 +160,7 @@ public:
|
|||||||
k_param_mode4,
|
k_param_mode4,
|
||||||
k_param_mode5,
|
k_param_mode5,
|
||||||
k_param_mode6,
|
k_param_mode6,
|
||||||
k_param_learn_channel,
|
k_param_aux_channel,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 220: Waypoint data
|
// 220: Waypoint data
|
||||||
|
@ -377,7 +377,6 @@ private:
|
|||||||
ModeManual mode_manual;
|
ModeManual mode_manual;
|
||||||
ModeGuided mode_guided;
|
ModeGuided mode_guided;
|
||||||
ModeAuto mode_auto;
|
ModeAuto mode_auto;
|
||||||
ModeLearning mode_learning;
|
|
||||||
ModeSteering mode_steering;
|
ModeSteering mode_steering;
|
||||||
ModeRTL mode_rtl;
|
ModeRTL mode_rtl;
|
||||||
|
|
||||||
|
@ -93,26 +93,6 @@
|
|||||||
#error XXX
|
#error XXX
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(MODE_1)
|
|
||||||
#define MODE_1 LEARNING
|
|
||||||
#endif
|
|
||||||
#if !defined(MODE_2)
|
|
||||||
#define MODE_2 LEARNING
|
|
||||||
#endif
|
|
||||||
#if !defined(MODE_3)
|
|
||||||
#define MODE_3 LEARNING
|
|
||||||
#endif
|
|
||||||
#if !defined(MODE_4)
|
|
||||||
#define MODE_4 LEARNING
|
|
||||||
#endif
|
|
||||||
#if !defined(MODE_5)
|
|
||||||
#define MODE_5 LEARNING
|
|
||||||
#endif
|
|
||||||
#if !defined(MODE_6)
|
|
||||||
#define MODE_6 MANUAL
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// STARTUP BEHAVIOUR
|
// STARTUP BEHAVIOUR
|
||||||
|
@ -9,9 +9,6 @@ Mode *Rover::control_mode_from_num(const enum mode num)
|
|||||||
case MANUAL:
|
case MANUAL:
|
||||||
ret = &mode_manual;
|
ret = &mode_manual;
|
||||||
break;
|
break;
|
||||||
case LEARNING:
|
|
||||||
ret = &mode_learning;
|
|
||||||
break;
|
|
||||||
case STEERING:
|
case STEERING:
|
||||||
ret = &mode_steering;
|
ret = &mode_steering;
|
||||||
break;
|
break;
|
||||||
|
@ -27,7 +27,6 @@ enum ch7_option {
|
|||||||
// ----------------
|
// ----------------
|
||||||
enum mode {
|
enum mode {
|
||||||
MANUAL = 0,
|
MANUAL = 0,
|
||||||
LEARNING = 2,
|
|
||||||
STEERING = 3,
|
STEERING = 3,
|
||||||
HOLD = 4,
|
HOLD = 4,
|
||||||
AUTO = 10,
|
AUTO = 10,
|
||||||
|
@ -265,17 +265,6 @@ public:
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
class ModeLearning : public ModeManual
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
|
|
||||||
uint32_t mode_number() const override { return LEARNING; }
|
|
||||||
|
|
||||||
// attributes for mavlink system status reporting
|
|
||||||
bool has_manual_input() const override { return true; }
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
class ModeRTL : public Mode
|
class ModeRTL : public Mode
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -1,2 +0,0 @@
|
|||||||
#include "mode.h"
|
|
||||||
#include "Rover.h"
|
|
@ -289,9 +289,6 @@ void Rover::notify_mode(enum mode new_mode)
|
|||||||
case MANUAL:
|
case MANUAL:
|
||||||
notify.set_flight_mode_str("MANU");
|
notify.set_flight_mode_str("MANU");
|
||||||
break;
|
break;
|
||||||
case LEARNING:
|
|
||||||
notify.set_flight_mode_str("LERN");
|
|
||||||
break;
|
|
||||||
case STEERING:
|
case STEERING:
|
||||||
notify.set_flight_mode_str("STER");
|
notify.set_flight_mode_str("STER");
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user