Browse Source

Copter: move rally-point handling up

mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
480a83fdef
  1. 71
      ArduCopter/GCS_Mavlink.cpp
  2. 1
      ArduCopter/GCS_Mavlink.h

71
ArduCopter/GCS_Mavlink.cpp

@ -1848,68 +1848,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) @@ -1848,68 +1848,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
#endif
break;
#if AC_RALLY == ENABLED
// receive a rally point from GCS and store in EEPROM
case MAVLINK_MSG_ID_RALLY_POINT: {
mavlink_rally_point_t packet;
mavlink_msg_rally_point_decode(msg, &packet);
if (packet.idx >= copter.rally.get_rally_total() ||
packet.idx >= copter.rally.get_rally_max()) {
send_text(MAV_SEVERITY_NOTICE,"Bad rally point message ID");
break;
}
if (packet.count != copter.rally.get_rally_total()) {
send_text(MAV_SEVERITY_NOTICE,"Bad rally point message count");
break;
}
// sanity check location
if (!check_latlng(packet.lat, packet.lng)) {
break;
}
RallyLocation rally_point;
rally_point.lat = packet.lat;
rally_point.lng = packet.lng;
rally_point.alt = packet.alt;
rally_point.break_alt = packet.break_alt;
rally_point.land_dir = packet.land_dir;
rally_point.flags = packet.flags;
if (!copter.rally.set_rally_point_with_index(packet.idx, rally_point)) {
send_text(MAV_SEVERITY_CRITICAL, "Error setting rally point");
}
break;
}
//send a rally point to the GCS
case MAVLINK_MSG_ID_RALLY_FETCH_POINT: {
mavlink_rally_fetch_point_t packet;
mavlink_msg_rally_fetch_point_decode(msg, &packet);
if (packet.idx > copter.rally.get_rally_total()) {
send_text(MAV_SEVERITY_NOTICE, "Bad rally point index");
break;
}
RallyLocation rally_point;
if (!copter.rally.get_rally_point_with_index(packet.idx, rally_point)) {
send_text(MAV_SEVERITY_NOTICE, "Failed to set rally point");
break;
}
mavlink_msg_rally_point_send_buf(msg,
chan, msg->sysid, msg->compid, packet.idx,
copter.rally.get_rally_total(), rally_point.lat, rally_point.lng,
rally_point.alt, rally_point.break_alt, rally_point.land_dir,
rally_point.flags);
break;
}
#endif // AC_RALLY == ENABLED
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
send_autopilot_version(FIRMWARE_VERSION);
break;
@ -2037,3 +1975,12 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission() @@ -2037,3 +1975,12 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission()
{
return &copter.mission;
}
AP_Rally *GCS_MAVLINK_Copter::get_rally() const
{
#if AC_RALLY == ENABLED
return &copter.rally;
#else
return nullptr;
#endif
}

1
ArduCopter/GCS_Mavlink.h

@ -19,6 +19,7 @@ protected: @@ -19,6 +19,7 @@ protected:
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
uint8_t sysid_my_gcs() const override;

Loading…
Cancel
Save