mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Rover: RTL within auto mode
This commit is contained in:
parent
14d9e932ab
commit
b60cb536ab
@ -32,6 +32,7 @@ Rover::Rover(void) :
|
|||||||
nav_controller(&L1_controller),
|
nav_controller(&L1_controller),
|
||||||
control_mode(&mode_initializing),
|
control_mode(&mode_initializing),
|
||||||
home(ahrs.get_home()),
|
home(ahrs.get_home()),
|
||||||
G_Dt(0.02f)
|
G_Dt(0.02f),
|
||||||
|
mode_auto(mode_rtl)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -211,7 +211,8 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
void Rover::do_RTL(void)
|
void Rover::do_RTL(void)
|
||||||
{
|
{
|
||||||
set_mode(mode_rtl, MODE_REASON_MISSION_COMMAND);
|
// start rtl in auto mode
|
||||||
|
mode_auto.start_RTL();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool stay_active_at_dest)
|
void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool stay_active_at_dest)
|
||||||
@ -307,7 +308,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
bool Rover::verify_RTL()
|
bool Rover::verify_RTL()
|
||||||
{
|
{
|
||||||
return mode_rtl.reached_destination();
|
return mode_auto.reached_destination();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Rover::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
bool Rover::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
||||||
|
@ -6,6 +6,9 @@
|
|||||||
|
|
||||||
#define MODE_NEXT_HEADING_UNKNOWN 99999.0f // used to indicate to set_desired_location method that next leg's heading is unknown
|
#define MODE_NEXT_HEADING_UNKNOWN 99999.0f // used to indicate to set_desired_location method that next leg's heading is unknown
|
||||||
|
|
||||||
|
// pre-define ModeRTL so Auto can appear higher in this file
|
||||||
|
class ModeRTL;
|
||||||
|
|
||||||
class Mode
|
class Mode
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@ -142,6 +145,9 @@ class ModeAuto : public Mode
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
// constructor
|
||||||
|
ModeAuto(ModeRTL& mode_rtl);
|
||||||
|
|
||||||
uint32_t mode_number() const override { return AUTO; }
|
uint32_t mode_number() const override { return AUTO; }
|
||||||
|
|
||||||
// methods that affect movement of the vehicle in this mode
|
// methods that affect movement of the vehicle in this mode
|
||||||
@ -164,6 +170,9 @@ public:
|
|||||||
void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) override;
|
void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) override;
|
||||||
bool reached_heading();
|
bool reached_heading();
|
||||||
|
|
||||||
|
// start RTL (within auto)
|
||||||
|
void start_RTL();
|
||||||
|
|
||||||
// execute the mission in reverse (i.e. backing up)
|
// execute the mission in reverse (i.e. backing up)
|
||||||
void set_reversed(bool value);
|
void set_reversed(bool value);
|
||||||
|
|
||||||
@ -174,13 +183,17 @@ protected:
|
|||||||
|
|
||||||
enum AutoSubMode {
|
enum AutoSubMode {
|
||||||
Auto_WP, // drive to a given location
|
Auto_WP, // drive to a given location
|
||||||
Auto_HeadingAndSpeed // turn to a given heading
|
Auto_HeadingAndSpeed, // turn to a given heading
|
||||||
|
Auto_RTL // perform RTL within auto mode
|
||||||
} _submode;
|
} _submode;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
bool check_trigger(void);
|
bool check_trigger(void);
|
||||||
|
|
||||||
|
// references
|
||||||
|
ModeRTL& _mode_rtl;
|
||||||
|
|
||||||
// this is set to true when auto has been triggered to start
|
// this is set to true when auto has been triggered to start
|
||||||
bool auto_triggered;
|
bool auto_triggered;
|
||||||
|
|
||||||
|
@ -1,6 +1,12 @@
|
|||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
|
// constructor
|
||||||
|
ModeAuto::ModeAuto(ModeRTL& mode_rtl) :
|
||||||
|
_mode_rtl(mode_rtl)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
bool ModeAuto::_enter()
|
bool ModeAuto::_enter()
|
||||||
{
|
{
|
||||||
// fail to enter auto if no mission commands
|
// fail to enter auto if no mission commands
|
||||||
@ -75,6 +81,10 @@ void ModeAuto::update()
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case Auto_RTL:
|
||||||
|
_mode_rtl.update();
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -94,6 +104,9 @@ bool ModeAuto::reached_destination()
|
|||||||
if (_submode == Auto_WP) {
|
if (_submode == Auto_WP) {
|
||||||
return _reached_destination;
|
return _reached_destination;
|
||||||
}
|
}
|
||||||
|
if (_submode == Auto_RTL) {
|
||||||
|
return _mode_rtl.reached_destination();
|
||||||
|
}
|
||||||
// we should never reach here but just in case, return true to allow missions to continue
|
// we should never reach here but just in case, return true to allow missions to continue
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -118,6 +131,14 @@ bool ModeAuto::reached_heading()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// start RTL (within auto)
|
||||||
|
void ModeAuto::start_RTL()
|
||||||
|
{
|
||||||
|
if (_mode_rtl.enter()) {
|
||||||
|
_submode = Auto_RTL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// execute the mission in reverse (i.e. backing up)
|
// execute the mission in reverse (i.e. backing up)
|
||||||
void ModeAuto::set_reversed(bool value)
|
void ModeAuto::set_reversed(bool value)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user