26 #if AP_TERRAIN_AVAILABLE 33 void AP_Terrain::update_mission_data(
void)
35 if (last_mission_change_ms != mission.last_change_time_ms() ||
36 last_mission_spacing != grid_spacing) {
38 next_mission_index = 1;
40 last_mission_change_ms = mission.last_change_time_ms();
41 last_mission_spacing = grid_spacing;
43 if (next_mission_index == 0) {
48 uint16_t pending, loaded;
49 get_statistics(pending, loaded);
57 for (uint8_t i=0; i<20; i++) {
60 if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
62 next_mission_index = 0;
68 while ((cmd.
id != MAV_CMD_NAV_WAYPOINT &&
69 cmd.
id != MAV_CMD_NAV_SPLINE_WAYPOINT) ||
72 if (!mission.read_cmd_from_storage(next_mission_index, cmd)) {
74 next_mission_index = 0;
83 if (next_mission_pos != 4) {
96 if (next_mission_pos == 5) {
98 hal.
console->
printf(
"checked waypoint %u\n", (
unsigned)next_mission_index);
102 next_mission_index++;
103 next_mission_pos = 0;
111 void AP_Terrain::update_rally_data(
void)
113 if (last_rally_change_ms != rally.last_change_time_ms() ||
114 last_rally_spacing != grid_spacing) {
116 next_rally_index = 1;
117 last_rally_change_ms = rally.last_change_time_ms();
118 last_rally_spacing = grid_spacing;
120 if (next_rally_index == 0) {
125 uint16_t pending, loaded;
126 get_statistics(pending, loaded);
135 if (!rally.get_rally_point_with_index(next_rally_index, rp)) {
137 next_rally_index = 0;
145 if (!height_amsl(loc, height,
false)) {
152 hal.
console->
printf(
"checked rally point %u\n", (
unsigned)next_rally_index);
160 #endif // AP_TERRAIN_AVAILABLE void location_update(struct Location &loc, float bearing, float distance)
AP_HAL::UARTDriver * console
Interface definition for the various Ground Control System.
int32_t lat
param 3 - Latitude * 10**7
virtual void printf(const char *,...) FMT_PRINTF(2
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
Receiving valid messages and 3D lock.