APM:Libraries
TerrainMission.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  handle checking mission points for terrain data
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <AP_Common/AP_Common.h>
21 #include <AP_Math/AP_Math.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include "AP_Terrain.h"
25 
26 #if AP_TERRAIN_AVAILABLE
27 
28 extern const AP_HAL::HAL& hal;
29 
30 /*
31  check that we have fetched all mission terrain data
32  */
33 void AP_Terrain::update_mission_data(void)
34 {
35  if (last_mission_change_ms != mission.last_change_time_ms() ||
36  last_mission_spacing != grid_spacing) {
37  // the mission has changed - start again
38  next_mission_index = 1;
39  next_mission_pos = 0;
40  last_mission_change_ms = mission.last_change_time_ms();
41  last_mission_spacing = grid_spacing;
42  }
43  if (next_mission_index == 0) {
44  // nothing to do
45  return;
46  }
47 
48  uint16_t pending, loaded;
49  get_statistics(pending, loaded);
50  if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
51  // wait till we have fully filled the current set of grids
52  return;
53  }
54 
55  // don't do more than 20 waypoints at a time, to prevent too much
56  // CPU usage
57  for (uint8_t i=0; i<20; i++) {
58  // get next mission command
60  if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
61  // nothing more to do
62  next_mission_index = 0;
63  return;
64  }
65 
66  // we only want nav waypoint commands. That should be enough to
67  // prefill the terrain data and makes many things much simpler
68  while ((cmd.id != MAV_CMD_NAV_WAYPOINT &&
69  cmd.id != MAV_CMD_NAV_SPLINE_WAYPOINT) ||
70  (cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
71  next_mission_index++;
72  if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
73  // nothing more to do
74  next_mission_index = 0;
75  next_mission_pos = 0;
76  return;
77  }
78  }
79 
80  // we will fetch 5 points around the waypoint. Four at 10 grid
81  // spacings away at 45, 135, 225 and 315 degrees, and the
82  // point itself
83  if (next_mission_pos != 4) {
84  location_update(cmd.content.location, 45+90*next_mission_pos, grid_spacing.get() * 10);
85  }
86 
87  // we have a mission command to check
88  float height;
89  if (!height_amsl(cmd.content.location, height, false)) {
90  // if we can't get data for a mission item then return and
91  // check again next time
92  return;
93  }
94 
95  next_mission_pos++;
96  if (next_mission_pos == 5) {
97 #if TERRAIN_DEBUG
98  hal.console->printf("checked waypoint %u\n", (unsigned)next_mission_index);
99 #endif
100 
101  // move to next waypoint
102  next_mission_index++;
103  next_mission_pos = 0;
104  }
105  }
106 }
107 
108 /*
109  check that we have fetched all rally terrain data
110  */
111 void AP_Terrain::update_rally_data(void)
112 {
113  if (last_rally_change_ms != rally.last_change_time_ms() ||
114  last_rally_spacing != grid_spacing) {
115  // a rally point has changed - start again
116  next_rally_index = 1;
117  last_rally_change_ms = rally.last_change_time_ms();
118  last_rally_spacing = grid_spacing;
119  }
120  if (next_rally_index == 0) {
121  // nothing to do
122  return;
123  }
124 
125  uint16_t pending, loaded;
126  get_statistics(pending, loaded);
127  if (pending && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
128  // wait till we have fully filled the current set of grids
129  return;
130  }
131 
132  while (true) {
133  // get next rally point
134  struct RallyLocation rp;
135  if (!rally.get_rally_point_with_index(next_rally_index, rp)) {
136  // nothing more to do
137  next_rally_index = 0;
138  return;
139  }
140 
141  Location loc;
142  loc.lat = rp.lat;
143  loc.lng = rp.lng;
144  float height;
145  if (!height_amsl(loc, height, false)) {
146  // if we can't get data for a rally item then return and
147  // check again next time
148  return;
149  }
150 
151 #if TERRAIN_DEBUG
152  hal.console->printf("checked rally point %u\n", (unsigned)next_rally_index);
153 #endif
154 
155  // move to next rally point
156  next_rally_index++;
157  }
158 }
159 
160 #endif // AP_TERRAIN_AVAILABLE
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
AP_HAL::UARTDriver * console
Definition: HAL.h:110
Interface definition for the various Ground Control System.
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100