mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: add support for more MISSION_CURRENT fields
- a state so someone can see if the mission is complete - total number of waypoints
This commit is contained in:
parent
82adf42bd6
commit
510ed4cf2f
|
@ -323,6 +323,12 @@ public:
|
|||
// mission item index to be sent on queued msg, delayed or not
|
||||
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
|
||||
|
||||
// generate a MISSION_STATE enumeration value for where the
|
||||
// mission is up to:
|
||||
MISSION_STATE mission_state(const class AP_Mission &mission) const;
|
||||
// send a mission_current message for the supplied waypoint
|
||||
void send_mission_current(const class AP_Mission &mission, uint16_t seq);
|
||||
|
||||
// common send functions
|
||||
void send_heartbeat(void) const;
|
||||
void send_meminfo(void);
|
||||
|
|
|
@ -613,7 +613,46 @@ void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg)
|
|||
prot->handle_mission_request(*this, packet, msg);
|
||||
}
|
||||
|
||||
// returns a MISSION_STATE numeration value best describing out
|
||||
// current mission state.
|
||||
MISSION_STATE GCS_MAVLINK::mission_state(const AP_Mission &mission) const
|
||||
{
|
||||
if (mission.num_commands() < 2) { // 1 means just home is present
|
||||
return MISSION_STATE_NO_MISSION;
|
||||
}
|
||||
switch (mission.state()) {
|
||||
case AP_Mission::mission_state::MISSION_STOPPED:
|
||||
return MISSION_STATE_NOT_STARTED;
|
||||
case AP_Mission::mission_state::MISSION_RUNNING:
|
||||
return MISSION_STATE_ACTIVE;
|
||||
case AP_Mission::mission_state::MISSION_COMPLETE:
|
||||
return MISSION_STATE_COMPLETE;
|
||||
}
|
||||
|
||||
// compiler ensures we can't get here as no default case in above enumeration
|
||||
|
||||
return MISSION_STATE_UNKNOWN;
|
||||
}
|
||||
|
||||
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
|
||||
void GCS_MAVLINK::send_mission_current(const class AP_Mission &mission, uint16_t seq)
|
||||
{
|
||||
auto num_commands = mission.num_commands();
|
||||
if (num_commands > 0) {
|
||||
// exclude home location from the count; see message definition.
|
||||
num_commands -= 1;
|
||||
}
|
||||
|
||||
const uint8_t mission_mode = AP::vehicle()->current_mode_requires_mission() ? 1 : 0;
|
||||
|
||||
mavlink_msg_mission_current_send(
|
||||
chan,
|
||||
seq,
|
||||
num_commands, // total
|
||||
mission_state(mission), // mission_state
|
||||
mission_mode); // mission_mode
|
||||
}
|
||||
|
||||
/*
|
||||
handle a MISSION_SET_CURRENT mavlink packet
|
||||
|
||||
|
@ -642,7 +681,7 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_
|
|||
// exactly that sequence number in it, even if ArduPilot never
|
||||
// actually holds that as a sequence number (e.g. packet.seq==0).
|
||||
if (HAVE_PAYLOAD_SPACE(chan, MISSION_CURRENT)) {
|
||||
mavlink_msg_mission_current_send(chan, packet.seq);
|
||||
send_mission_current(mission, packet.seq);
|
||||
} else {
|
||||
// schedule it for later:
|
||||
send_message(MSG_CURRENT_WAYPOINT);
|
||||
|
@ -5116,7 +5155,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
|||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
||||
AP_Mission *mission = AP::mission();
|
||||
if (mission != nullptr) {
|
||||
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
|
||||
send_mission_current(*mission, mission->get_current_nav_index());
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue