Skip to content

Commit

Permalink
Sub: add support for AVAILABLE_MODES msg
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Nov 12, 2024
1 parent a341259 commit 1abdd79
Show file tree
Hide file tree
Showing 3 changed files with 65 additions and 1 deletion.
47 changes: 46 additions & 1 deletion ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -437,7 +437,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};

const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
Expand Down Expand Up @@ -962,3 +963,47 @@ uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&sub.mode_manual,
&sub.mode_stabilize,
&sub.mode_acro,
&sub.mode_althold,
&sub.mode_surftrak,
&sub.mode_poshold,
&sub.mode_auto,
&sub.mode_guided,
&sub.mode_circle,
&sub.mode_surface,
&sub.mode_motordetect,
};

const uint8_t mode_count = ARRAY_SIZE(modes);

// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}

// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();

mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);

return mode_count;
}
4 changes: 4 additions & 0 deletions ArduSub/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,10 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK {

uint64_t capabilities() const override;

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;

private:

void handle_message(const mavlink_message_t &msg) override;
Expand Down
15 changes: 15 additions & 0 deletions ArduSub/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,9 @@ class Mode
virtual const char *name() const = 0;
virtual const char *name4() const = 0;

// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;

// functions for reporting to GCS
virtual bool get_wp(Location &loc) { return false; }
virtual int32_t wp_bearing() const { return 0; }
Expand Down Expand Up @@ -202,6 +205,7 @@ class ModeManual : public Mode

const char *name() const override { return "MANUAL"; }
const char *name4() const override { return "MANU"; }
Mode::Number number() const override { return Mode::Number::MANUAL; }
};


Expand All @@ -224,6 +228,7 @@ class ModeAcro : public Mode

const char *name() const override { return "ACRO"; }
const char *name4() const override { return "ACRO"; }
Mode::Number number() const override { return Mode::Number::ACRO; }
};


Expand All @@ -246,6 +251,7 @@ class ModeStabilize : public Mode

const char *name() const override { return "STABILIZE"; }
const char *name4() const override { return "STAB"; }
Mode::Number number() const override { return Mode::Number::STABILIZE; }
};


Expand All @@ -272,6 +278,7 @@ class ModeAlthold : public Mode

const char *name() const override { return "ALT_HOLD"; }
const char *name4() const override { return "ALTH"; }
Mode::Number number() const override { return Mode::Number::ALT_HOLD; }
};


Expand All @@ -293,6 +300,7 @@ class ModeSurftrak : public ModeAlthold

const char *name() const override { return "SURFTRAK"; }
const char *name4() const override { return "STRK"; }
Mode::Number number() const override { return Mode::Number::SURFTRAK; }

private:

Expand Down Expand Up @@ -342,6 +350,8 @@ class ModeGuided : public Mode

const char *name() const override { return "GUIDED"; }
const char *name4() const override { return "GUID"; }
Mode::Number number() const override { return Mode::Number::GUIDED; }

autopilot_yaw_mode get_default_auto_yaw_mode(bool rtl) const;

private:
Expand Down Expand Up @@ -387,6 +397,7 @@ class ModeAuto : public ModeGuided

const char *name() const override { return "AUTO"; }
const char *name4() const override { return "AUTO"; }
Mode::Number number() const override { return Mode::Number::AUTO; }

private:
void auto_wp_run();
Expand Down Expand Up @@ -417,6 +428,7 @@ class ModePoshold : public ModeAlthold

const char *name() const override { return "POSHOLD"; }
const char *name4() const override { return "POSH"; }
Mode::Number number() const override { return Mode::Number::POSHOLD; }
};


Expand All @@ -439,6 +451,7 @@ class ModeCircle : public Mode

const char *name() const override { return "CIRCLE"; }
const char *name4() const override { return "CIRC"; }
Mode::Number number() const override { return Mode::Number::CIRCLE; }
};

class ModeSurface : public Mode
Expand All @@ -460,6 +473,7 @@ class ModeSurface : public Mode

const char *name() const override { return "SURFACE"; }
const char *name4() const override { return "SURF"; }
Mode::Number number() const override { return Mode::Number::CIRCLE; }
};


Expand All @@ -482,4 +496,5 @@ class ModeMotordetect : public Mode

const char *name() const override { return "MOTORDETECT"; }
const char *name4() const override { return "DETE"; }
Mode::Number number() const override { return Mode::Number::MOTOR_DETECT; }
};

0 comments on commit 1abdd79

Please sign in to comment.