Browse Source

AP_Terrain: stop passing mission in Terrain constructor

Terrain can use the mission singleton

This means Copter can have terrain while compiling mission out
gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
6b21d117a9
  1. 3
      libraries/AP_Terrain/AP_Terrain.cpp
  2. 11
      libraries/AP_Terrain/AP_Terrain.h
  3. 16
      libraries/AP_Terrain/TerrainMission.cpp

3
libraries/AP_Terrain/AP_Terrain.cpp

@ -72,8 +72,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { @@ -72,8 +72,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
};
// constructor
AP_Terrain::AP_Terrain(const AP_Mission &_mission) :
mission(_mission),
AP_Terrain::AP_Terrain() :
disk_io_state(DiskIoIdle),
fd(-1)
{

11
libraries/AP_Terrain/AP_Terrain.h

@ -18,6 +18,7 @@ @@ -18,6 +18,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/Location.h>
#include <AP_Filesystem/AP_Filesystem_Available.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#ifndef AP_TERRAIN_AVAILABLE
#if HAVE_FILESYSTEM_SUPPORT && defined(HAL_BOARD_TERRAIN_DIRECTORY)
@ -30,7 +31,6 @@ @@ -30,7 +31,6 @@
#if AP_TERRAIN_AVAILABLE
#include <AP_Param/AP_Param.h>
#include <AP_Mission/AP_Mission.h>
#define TERRAIN_DEBUG 0
@ -83,11 +83,10 @@ @@ -83,11 +83,10 @@
class AP_Terrain {
public:
AP_Terrain(const AP_Mission &_mission);
AP_Terrain();
/* Do not allow copies */
AP_Terrain(const AP_Terrain &other) = delete;
AP_Terrain &operator=(const AP_Terrain&) = delete;
CLASS_NO_COPY(AP_Terrain);
static AP_Terrain *get_singleton(void) { return singleton; }
@ -360,10 +359,6 @@ private: @@ -360,10 +359,6 @@ private:
DisableDownload = (1U<<0),
};
// reference to AP_Mission, so we can ask preload terrain data for
// all waypoints
const AP_Mission &mission;
// cache of grids in memory, LRU
uint8_t cache_size = 0;
struct grid_cache *cache = nullptr;

16
libraries/AP_Terrain/TerrainMission.cpp

@ -19,6 +19,7 @@ @@ -19,6 +19,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Rally/AP_Rally.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/GCS.h>
@ -34,12 +35,18 @@ extern const AP_HAL::HAL& hal; @@ -34,12 +35,18 @@ extern const AP_HAL::HAL& hal;
*/
void AP_Terrain::update_mission_data(void)
{
if (last_mission_change_ms != mission.last_change_time_ms() ||
#if HAL_MISSION_ENABLED
const AP_Mission *mission = AP::mission();
if (mission == nullptr) {
return;
}
if (last_mission_change_ms != mission->last_change_time_ms() ||
last_mission_spacing != grid_spacing) {
// the mission has changed - start again
next_mission_index = 1;
next_mission_pos = 0;
last_mission_change_ms = mission.last_change_time_ms();
last_mission_change_ms = mission->last_change_time_ms();
last_mission_spacing = grid_spacing;
}
if (next_mission_index == 0) {
@ -59,7 +66,7 @@ void AP_Terrain::update_mission_data(void) @@ -59,7 +66,7 @@ void AP_Terrain::update_mission_data(void)
for (uint8_t i=0; i<20; i++) {
// get next mission command
AP_Mission::Mission_Command cmd;
if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
if (!mission->read_cmd_from_storage(next_mission_index, cmd)) {
// nothing more to do
next_mission_index = 0;
return;
@ -71,7 +78,7 @@ void AP_Terrain::update_mission_data(void) @@ -71,7 +78,7 @@ void AP_Terrain::update_mission_data(void)
cmd.id != MAV_CMD_NAV_SPLINE_WAYPOINT) ||
(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
next_mission_index++;
if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
if (!mission->read_cmd_from_storage(next_mission_index, cmd)) {
// nothing more to do
next_mission_index = 0;
next_mission_pos = 0;
@ -105,6 +112,7 @@ void AP_Terrain::update_mission_data(void) @@ -105,6 +112,7 @@ void AP_Terrain::update_mission_data(void)
next_mission_pos = 0;
}
}
#endif // HAL_MISSION_ENABLED
}
/*

Loading…
Cancel
Save