Skip to content

Commit

Permalink
Merge branch 'master' into master_JRE
Browse files Browse the repository at this point in the history
  • Loading branch information
jfbblue0922 authored Oct 31, 2023
2 parents 36565ae + f1b6a7d commit e9f3dec
Show file tree
Hide file tree
Showing 108 changed files with 941 additions and 580 deletions.
2 changes: 2 additions & 0 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -279,8 +279,10 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_NAV_CONTROLLER_OUTPUT,
MSG_GPS_RAW,
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
MSG_GPS2_RAW,
MSG_GPS2_RTK,
#endif
};
static const ap_message STREAM_POSITION_msgs[] = {
MSG_LOCATION,
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -237,6 +237,8 @@ class Copter : public AP_Vehicle {

friend class _AutoTakeoff;

friend class PayloadPlace;

Copter(void);

private:
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -508,8 +508,10 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
MSG_GPS_RAW,
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
MSG_GPS2_RAW,
MSG_GPS2_RTK,
#endif
MSG_NAV_CONTROLLER_OUTPUT,
#if AP_FENCE_ENABLED
MSG_FENCE_STATUS,
Expand Down Expand Up @@ -569,7 +571,9 @@ static const ap_message STREAM_PARAMS_msgs[] = {
};
static const ap_message STREAM_ADSB_msgs[] = {
MSG_ADSB_VEHICLE,
#if AP_AIS_ENABLED
MSG_AIS_VESSEL,
#endif
};

const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
Expand Down
4 changes: 1 addition & 3 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,9 +154,7 @@ void Mode::AutoYaw::set_roi(const Location &roi_location)
auto_yaw.set_mode_to_default(false);
#if HAL_MOUNT_ENABLED
// switch off the camera tracking if enabled
if (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
copter.camera_mount.set_mode_to_default();
}
copter.camera_mount.clear_roi_target();
#endif // HAL_MOUNT_ENABLED
} else {
#if HAL_MOUNT_ENABLED
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -638,3 +638,7 @@
#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED
#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED
#endif

#ifndef AC_PAYLOAD_PLACE_ENABLED
#define AC_PAYLOAD_PLACE_ENABLED 1
#endif
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
4 changes: 4 additions & 0 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@ Mode::Mode(void) :
G_Dt(copter.G_Dt)
{ };

#if AC_PAYLOAD_PLACE_ENABLED
PayloadPlace Mode::payload_place;
#endif

// return the static controller object corresponding to supplied mode
Mode *Copter::mode_from_mode_num(const Mode::Number mode)
{
Expand Down
60 changes: 43 additions & 17 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,41 @@ class _AutoTakeoff {
Vector3p complete_pos; // target takeoff position as offset from ekf origin in cm
};

#if AC_PAYLOAD_PLACE_ENABLED
class PayloadPlace {
public:
void run();
void start_descent();
bool verify();

enum class State : uint8_t {
FlyToLocation,
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;

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;
};
#endif

class Mode {
friend class PayloadPlace;

public:

Expand Down Expand Up @@ -167,6 +201,11 @@ class Mode {
land_run_vertical_control(pause_descent);
}

#if AC_PAYLOAD_PLACE_ENABLED
// payload place flight behaviour:
static PayloadPlace payload_place;
#endif

// 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 @@ -432,10 +471,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 All @@ -461,7 +501,9 @@ class ModeAuto : public Mode {
NAVGUIDED,
LOITER,
LOITER_TO_ALT,
#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
NAV_PAYLOAD_PLACE,
#endif
NAV_SCRIPT_TIME,
NAV_ATTITUDE_TIME,
};
Expand Down Expand Up @@ -556,12 +598,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

bool shift_alt_to_current_alt(Location& target_loc) const;
Expand Down Expand Up @@ -649,16 +685,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 e9f3dec

Please sign in to comment.