2014-08-06 06:32:53 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
handle checking mission points for terrain data
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
2022-02-01 23:28:33 -04:00
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2019-01-08 07:42:29 -04:00
|
|
|
#include <AP_Rally/AP_Rally.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2014-08-06 06:32:53 -03:00
|
|
|
#include "AP_Terrain.h"
|
2019-06-13 23:43:49 -03:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2014-08-06 06:32:53 -03:00
|
|
|
|
|
|
|
#if AP_TERRAIN_AVAILABLE
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
/*
|
|
|
|
check that we have fetched all mission terrain data
|
|
|
|
*/
|
|
|
|
void AP_Terrain::update_mission_data(void)
|
|
|
|
{
|
2022-08-14 20:08:16 -03:00
|
|
|
#if AP_MISSION_ENABLED
|
2022-02-01 23:28:33 -04:00
|
|
|
const AP_Mission *mission = AP::mission();
|
|
|
|
if (mission == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (last_mission_change_ms != mission->last_change_time_ms() ||
|
2014-08-06 06:32:53 -03:00
|
|
|
last_mission_spacing != grid_spacing) {
|
|
|
|
// the mission has changed - start again
|
|
|
|
next_mission_index = 1;
|
2014-08-25 01:55:15 -03:00
|
|
|
next_mission_pos = 0;
|
2022-02-01 23:28:33 -04:00
|
|
|
last_mission_change_ms = mission->last_change_time_ms();
|
2014-08-06 06:32:53 -03:00
|
|
|
last_mission_spacing = grid_spacing;
|
|
|
|
}
|
|
|
|
if (next_mission_index == 0) {
|
|
|
|
// nothing to do
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t pending, loaded;
|
|
|
|
get_statistics(pending, loaded);
|
2017-12-01 19:50:04 -04:00
|
|
|
if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// wait till we have fully filled the current set of grids
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// don't do more than 20 waypoints at a time, to prevent too much
|
|
|
|
// CPU usage
|
|
|
|
for (uint8_t i=0; i<20; i++) {
|
|
|
|
// get next mission command
|
|
|
|
AP_Mission::Mission_Command cmd;
|
2022-02-01 23:28:33 -04:00
|
|
|
if (!mission->read_cmd_from_storage(next_mission_index, cmd)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// nothing more to do
|
|
|
|
next_mission_index = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// we only want nav waypoint commands. That should be enough to
|
|
|
|
// prefill the terrain data and makes many things much simpler
|
2014-08-06 09:13:37 -03:00
|
|
|
while ((cmd.id != MAV_CMD_NAV_WAYPOINT &&
|
|
|
|
cmd.id != MAV_CMD_NAV_SPLINE_WAYPOINT) ||
|
|
|
|
(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
next_mission_index++;
|
2022-02-01 23:28:33 -04:00
|
|
|
if (!mission->read_cmd_from_storage(next_mission_index, cmd)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// nothing more to do
|
|
|
|
next_mission_index = 0;
|
2014-08-25 01:55:15 -03:00
|
|
|
next_mission_pos = 0;
|
2014-08-06 06:32:53 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-08-25 01:55:15 -03:00
|
|
|
// we will fetch 5 points around the waypoint. Four at 10 grid
|
|
|
|
// spacings away at 45, 135, 225 and 315 degrees, and the
|
|
|
|
// point itself
|
|
|
|
if (next_mission_pos != 4) {
|
2019-04-05 03:11:27 -03:00
|
|
|
cmd.content.location.offset_bearing(45+90*next_mission_pos, grid_spacing.get() * 10);
|
2014-08-25 01:55:15 -03:00
|
|
|
}
|
|
|
|
|
2014-08-06 06:32:53 -03:00
|
|
|
// we have a mission command to check
|
|
|
|
float height;
|
2022-01-31 00:35:06 -04:00
|
|
|
if (!height_amsl(cmd.content.location, height)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// if we can't get data for a mission item then return and
|
|
|
|
// check again next time
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-08-25 01:55:15 -03:00
|
|
|
next_mission_pos++;
|
|
|
|
if (next_mission_pos == 5) {
|
2014-08-06 06:32:53 -03:00
|
|
|
#if TERRAIN_DEBUG
|
2014-08-25 01:55:15 -03:00
|
|
|
hal.console->printf("checked waypoint %u\n", (unsigned)next_mission_index);
|
2014-08-06 06:32:53 -03:00
|
|
|
#endif
|
|
|
|
|
2014-08-25 01:55:15 -03:00
|
|
|
// move to next waypoint
|
|
|
|
next_mission_index++;
|
|
|
|
next_mission_pos = 0;
|
|
|
|
}
|
2014-08-06 06:32:53 -03:00
|
|
|
}
|
2022-08-14 20:08:16 -03:00
|
|
|
#endif // AP_MISSION_ENABLED
|
2014-08-06 06:32:53 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
check that we have fetched all rally terrain data
|
|
|
|
*/
|
|
|
|
void AP_Terrain::update_rally_data(void)
|
|
|
|
{
|
2019-01-08 07:42:29 -04:00
|
|
|
const AP_Rally *rally = AP::rally();
|
|
|
|
if (rally == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (last_rally_change_ms != rally->last_change_time_ms() ||
|
2014-08-06 06:32:53 -03:00
|
|
|
last_rally_spacing != grid_spacing) {
|
|
|
|
// a rally point has changed - start again
|
|
|
|
next_rally_index = 1;
|
2019-01-08 07:42:29 -04:00
|
|
|
last_rally_change_ms = rally->last_change_time_ms();
|
2014-08-06 06:32:53 -03:00
|
|
|
last_rally_spacing = grid_spacing;
|
|
|
|
}
|
|
|
|
if (next_rally_index == 0) {
|
|
|
|
// nothing to do
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t pending, loaded;
|
|
|
|
get_statistics(pending, loaded);
|
2017-12-01 19:50:04 -04:00
|
|
|
if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// wait till we have fully filled the current set of grids
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
while (true) {
|
|
|
|
// get next rally point
|
|
|
|
struct RallyLocation rp;
|
2019-01-08 07:42:29 -04:00
|
|
|
if (!rally->get_rally_point_with_index(next_rally_index, rp)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// nothing more to do
|
|
|
|
next_rally_index = 0;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
Location loc;
|
|
|
|
loc.lat = rp.lat;
|
|
|
|
loc.lng = rp.lng;
|
|
|
|
float height;
|
2022-01-31 00:35:06 -04:00
|
|
|
if (!height_amsl(loc, height)) {
|
2014-08-06 06:32:53 -03:00
|
|
|
// if we can't get data for a rally item then return and
|
|
|
|
// check again next time
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
#if TERRAIN_DEBUG
|
|
|
|
hal.console->printf("checked rally point %u\n", (unsigned)next_rally_index);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// move to next rally point
|
|
|
|
next_rally_index++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // AP_TERRAIN_AVAILABLE
|