Skip to content

Commit

Permalink
Copter: Payload Place split
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Oct 3, 2023
1 parent f3b8300 commit 28d41cb
Show file tree
Hide file tree
Showing 9 changed files with 1,533 additions and 173 deletions.
2 changes: 2 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -236,6 +236,8 @@ class Copter : public AP_Vehicle {
friend class ModeTurtle;
friend class AP_ExternalControl_Copter;

friend class PayloadPlace;

Copter(void);

private:
Expand Down
12 changes: 0 additions & 12 deletions ArduCopter/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,18 +76,6 @@ enum class AirMode {
AIRMODE_ENABLED,
};

enum PayloadPlaceStateType {
PayloadPlaceStateType_FlyToLocation,
PayloadPlaceStateType_Descent_Start,
PayloadPlaceStateType_Descent,
PayloadPlaceStateType_Release,
PayloadPlaceStateType_Releasing,
PayloadPlaceStateType_Delay,
PayloadPlaceStateType_Ascent_Start,
PayloadPlaceStateType_Ascent,
PayloadPlaceStateType_Done,
};

// bit options for DEV_OPTIONS parameter
enum DevOptions {
DevOptionADSBMAVLink = 1,
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ Mode::Mode(void) :
G_Dt(copter.G_Dt)
{ };

PayloadPlace Mode::payload_place;

// return the static controller object corresponding to supplied mode
Mode *Copter::mode_from_mode_num(const Mode::Number mode)
{
Expand Down
51 changes: 36 additions & 15 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,38 @@ class ParametersG2;

class GCS_Copter;

class PayloadPlace {
public:
void init(float descent_max);
void run();
bool done(){return state == State::Done;}

enum class State : uint8_t {
Descent_Start,
Descent,
Release,
Releasing,
Delay,
Ascent_Start,
Ascent,
Done,
};

// these are set by the Mission code:
State state = State::Descent_Start; // records state of payload place
float descent_max_cm;
bool horizontal_control = true;

private:
uint32_t descent_established_time_ms; // milliseconds
uint32_t place_start_time_ms; // milliseconds
float descent_thrust_level;
float descent_start_altitude_cm;
float descent_speed_cms;
};

class Mode {
friend class PayloadPlace;

public:

Expand Down Expand Up @@ -144,6 +175,9 @@ class Mode {
land_run_vertical_control(pause_descent);
}

// payload place flight behaviour:
static PayloadPlace payload_place;

// run normal or precision landing (if enabled)
// pause_descent is true if vehicle should not descend
void land_run_normal_or_precland(bool pause_descent = false);
Expand Down Expand Up @@ -423,10 +457,11 @@ class ModeAltHold : public Mode {

};


class ModeAuto : public Mode {

public:
friend class PayloadPlace; // in case wp_run is accidentally required

// inherit constructor
using Mode::Mode;
Number mode_number() const override { return auto_RTL? Number::AUTO_RTL : Number::AUTO; }
Expand Down Expand Up @@ -548,10 +583,6 @@ class ModeAuto : public Mode {
Location loc_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc) const;

void payload_place_run();
bool payload_place_run_should_run();
void payload_place_run_hover();
void payload_place_run_descent();
void payload_place_run_release();

SubMode _mode = SubMode::TAKEOFF; // controls which auto controller is run

Expand Down Expand Up @@ -640,16 +671,6 @@ class ModeAuto : public Mode {
};
State state = State::FlyToLocation;

struct {
PayloadPlaceStateType state = PayloadPlaceStateType_Descent_Start; // records state of payload place
uint32_t descent_established_time_ms; // milliseconds
uint32_t place_start_time_ms; // milliseconds
float descent_thrust_level;
float descent_start_altitude_cm;
float descent_speed_cms;
float descent_max_cm;
} nav_payload_place;

bool waiting_to_start; // true if waiting for vehicle to be armed or EKF origin before starting mission

// True if we have entered AUTO to perform a DO_LAND_START landing sequence and we should report as AUTO RTL mode
Expand Down
Loading

0 comments on commit 28d41cb

Please sign in to comment.