mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
GCS_MAVLink: upload fence when auto mode not complied
This commit is contained in:
parent
fc2090161b
commit
590d2fcf77
@ -3945,10 +3945,6 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
|
|||||||
|
|
||||||
void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg)
|
void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
AP_Mission *_mission = AP::mission();
|
|
||||||
if (_mission == nullptr) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
switch (msg.msgid) {
|
switch (msg.msgid) {
|
||||||
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
|
||||||
{
|
{
|
||||||
@ -3972,7 +3968,10 @@ void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg)
|
|||||||
|
|
||||||
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
|
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
|
||||||
{
|
{
|
||||||
|
AP_Mission *_mission = AP::mission();
|
||||||
|
if (_mission != nullptr) {
|
||||||
handle_mission_set_current(*_mission, msg);
|
handle_mission_set_current(*_mission, msg);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -5032,18 +5031,18 @@ void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) const {
|
|||||||
|
|
||||||
bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
||||||
{
|
{
|
||||||
AP_Mission *mission = AP::mission();
|
|
||||||
if (mission == nullptr) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool ret = true;
|
bool ret = true;
|
||||||
switch (id) {
|
switch (id) {
|
||||||
case MSG_CURRENT_WAYPOINT:
|
case MSG_CURRENT_WAYPOINT:
|
||||||
|
{
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
||||||
|
AP_Mission *mission = AP::mission();
|
||||||
|
if (mission != nullptr) {
|
||||||
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
|
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
|
||||||
|
}
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
case MSG_MISSION_ITEM_REACHED:
|
case MSG_MISSION_ITEM_REACHED:
|
||||||
CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
|
CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
|
||||||
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
||||||
|
Loading…
Reference in New Issue
Block a user