aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator/mission.cpp
blob: 879e5b6181afc7ed815f50a874c578b2f90ab869 (plain) (blame)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
/****************************************************************************
 *
 *   Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/
/**
 * @file navigator_mission.cpp
 *
 * Helper class to access missions
 *
 * @author Julian Oes <julian@oes.ch>
 */

#include <sys/types.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>

#include <drivers/drv_hrt.h>

#include <dataman/dataman.h>
#include <systemlib/err.h>
#include <geo/geo.h>

#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>

#include "navigator.h"
#include "mission.h"


Mission::Mission(Navigator *navigator, const char *name) :
	SuperBlock(NULL, name),
	_navigator(navigator),
	_first_run(true),
	_param_onboard_enabled(this, "ONBOARD_EN"),
	_param_loiter_radius(this, "LOITER_RAD"),
	_onboard_mission({0}),
	_offboard_mission({0}),
	_current_onboard_mission_index(-1),
	_current_offboard_mission_index(-1),
	_mission_item({0}),
	_mission_result_pub(-1),
	_mission_result({0}),
	_mission_type(MISSION_TYPE_NONE),
	_loiter_set(false)
{
	/* load initial params */
	updateParams();
	/* set initial mission items */
	reset();

}

Mission::~Mission()
{
}

void
Mission::reset()
{
	_first_run = true;
	_loiter_set = false;
}

bool
Mission::update(struct position_setpoint_triplet_s *pos_sp_triplet)
{

	/* check if anything has changed */
	bool onboard_updated = is_onboard_mission_updated();
	bool offboard_updated = is_offboard_mission_updated();

	bool updated = false;

	/* reset mission items if needed */
	if (onboard_updated || offboard_updated) {
		set_mission_items(pos_sp_triplet);
		updated = true;
		_first_run = false;
	}

	/* lets check if we reached the current mission item */
	if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
		advance_mission();
		set_mission_items(pos_sp_triplet);
		updated = true;
	}

	/* maybe we couldn't actually set a mission, therefore lets set a loiter setpoint */
	if (_mission_type == MISSION_TYPE_NONE && !_loiter_set) {
		bool use_current_pos_sp = (pos_sp_triplet->current.valid && _waypoint_position_reached);
		set_loiter_item(use_current_pos_sp, pos_sp_triplet);
		updated = true;
		_loiter_set = true;
	}
	return updated;
}

bool
Mission::is_mission_item_reached()
{
	/* TODO: count turns */
#if 0
	if ((_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
	     _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
	     _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
	    _mission_item.loiter_radius > 0.01f) {

		return false;
	}
#endif

	hrt_abstime now = hrt_absolute_time();

	if (!_waypoint_position_reached) {

		float dist = -1.0f;
		float dist_xy = -1.0f;
		float dist_z = -1.0f;

		float altitude_amsl = _mission_item.altitude_is_relative
				      ? _mission_item.altitude + _navigator->get_home_position()->alt
			              : _mission_item.altitude;

		dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, altitude_amsl,
				                          _navigator->get_global_position()->lat,
							  _navigator->get_global_position()->lon,
							  _navigator->get_global_position()->alt,
				&dist_xy, &dist_z);

		if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) {

			/* require only altitude for takeoff */
			if (_navigator->get_global_position()->alt > altitude_amsl - _mission_item.acceptance_radius) {
				_waypoint_position_reached = true;
			}
		} else {
			if (dist >= 0.0f && dist <= _mission_item.acceptance_radius) {
				_waypoint_position_reached = true;
			}
		}
	}

	if (_waypoint_position_reached && !_waypoint_yaw_reached) {

		/* TODO: removed takeoff, why? */
		if (_navigator->get_vstatus()->is_rotary_wing && isfinite(_mission_item.yaw)) {

			/* check yaw if defined only for rotary wing except takeoff */
			float yaw_err = _wrap_pi(_mission_item.yaw - _navigator->get_global_position()->yaw);

			if (fabsf(yaw_err) < 0.2f) { /* TODO: get rid of magic number */
				_waypoint_yaw_reached = true;
			}

		} else {
			_waypoint_yaw_reached = true;
		}
	}

	/* check if the current waypoint was reached */
	if (_waypoint_position_reached && _waypoint_yaw_reached) {

		if (_time_first_inside_orbit == 0) {
			_time_first_inside_orbit = now;

			// if (_mission_item.time_inside > 0.01f) {
			// 	mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs",
			// 		(double)_mission_item.time_inside);
			// }
		}

		/* check if the MAV was long enough inside the waypoint orbit */
		if (now - _time_first_inside_orbit >= (hrt_abstime)_mission_item.time_inside * 1e6f) {
			return true;
		}
	}
	return false;
}

void
Mission::reset_mission_item_reached()
{
	_waypoint_position_reached = false;
	_waypoint_yaw_reached = false;
	_time_first_inside_orbit = 0;
}

void
Mission::mission_item_to_position_setpoint(const struct mission_item_s *item, struct position_setpoint_s *sp)
{
	sp->valid = true;
	sp->lat = item->lat;
	sp->lon = item->lon;
	sp->alt = item->altitude_is_relative ? item->altitude + _navigator->get_home_position()->alt : item->altitude;
	sp->yaw = item->yaw;
	sp->loiter_radius = item->loiter_radius;
	sp->loiter_direction = item->loiter_direction;
	sp->pitch_min = item->pitch_min;

	if (item->nav_cmd == NAV_CMD_TAKEOFF) {
		sp->type = SETPOINT_TYPE_TAKEOFF;

	} else if (item->nav_cmd == NAV_CMD_LAND) {
		sp->type = SETPOINT_TYPE_LAND;

	} else if (item->nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
		   item->nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
		   item->nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
		sp->type = SETPOINT_TYPE_LOITER;

	} else {
		sp->type = SETPOINT_TYPE_POSITION;
	}
}

void
Mission::set_loiter_item(bool reuse_current_pos_sp, struct position_setpoint_triplet_s *pos_sp_triplet)
{
	if (reuse_current_pos_sp && pos_sp_triplet->current.valid) {
		/* nothing to be done, just use the current item */
	} else {
		pos_sp_triplet->current.lat = _navigator->get_global_position()->lat;
		pos_sp_triplet->current.lon = _navigator->get_global_position()->lon;
		pos_sp_triplet->current.alt = _navigator->get_global_position()->alt;
		pos_sp_triplet->current.yaw = NAN;	/* NAN means to use current yaw */
	}
	pos_sp_triplet->current.type = SETPOINT_TYPE_LOITER;
	pos_sp_triplet->current.loiter_radius = _param_loiter_radius.get();
	pos_sp_triplet->current.loiter_direction = 1;

	pos_sp_triplet->previous.valid = false;
	pos_sp_triplet->current.valid = true;
	pos_sp_triplet->next.valid = false;
}


bool
Mission::is_onboard_mission_updated()
{
	bool updated;
	orb_check(_navigator->get_onboard_mission_sub(), &updated);

	if (!updated && !_first_run) {
		return false;
	}

	if (orb_copy(ORB_ID(onboard_mission), _navigator->get_onboard_mission_sub(), &_onboard_mission) == OK) {
		/* accept the current index set by the onboard mission if it is within bounds */
		if (_onboard_mission.current_index >=0
		&& _onboard_mission.current_index < (int)_onboard_mission.count) {
			_current_onboard_mission_index = _onboard_mission.current_index;
		} else {
			/* if less WPs available, reset to first WP */
			if (_current_onboard_mission_index >= (int)_onboard_mission.count) {
				_current_onboard_mission_index = 0;
			/* if not initialized, set it to 0 */
			} else if (_current_onboard_mission_index < 0) {
				_current_onboard_mission_index = 0;
			}
			/* otherwise, just leave it */
		}
	} else {
		_onboard_mission.count = 0;
		_onboard_mission.current_index = 0;
		_current_onboard_mission_index = 0;
	}
	return true;
}

bool
Mission::is_offboard_mission_updated()
{
	bool updated;
	orb_check(_navigator->get_offboard_mission_sub(), &updated);

	if (!updated && !_first_run) {
		return false;
	}
	if (orb_copy(ORB_ID(offboard_mission), _navigator->get_offboard_mission_sub(), &_offboard_mission) == OK) {

		/* determine current index */
		if (_offboard_mission.current_index >= 0
		    && _offboard_mission.current_index < (int)_offboard_mission.count) {
			_current_offboard_mission_index = _offboard_mission.current_index;
		} else {
			/* if less WPs available, reset to first WP */
			if (_current_offboard_mission_index >= (int)_offboard_mission.count) {
				_current_offboard_mission_index = 0;
			/* if not initialized, set it to 0 */
			} else if (_current_offboard_mission_index < 0) {
				_current_offboard_mission_index = 0;
			}
			/* otherwise, just leave it */
		}

		/* Check mission feasibility, for now do not handle the return value,
		 * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
		dm_item_t dm_current;

		if (_offboard_mission.dataman_id == 0) {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
		} else {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
		}

		missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing, dm_current,
			                                      (size_t)_offboard_mission.count,
							      _navigator->get_geofence(),
							      _navigator->get_home_position()->alt);
	} else {
		_offboard_mission.count = 0;
		_offboard_mission.current_index = 0;
		_current_offboard_mission_index = 0;
	}
	return true;
}


void
Mission::advance_mission()
{
	switch (_mission_type) {
	case MISSION_TYPE_ONBOARD:
		_current_onboard_mission_index++;
		break;

	case MISSION_TYPE_OFFBOARD:
		_current_offboard_mission_index++;
		break;

	case MISSION_TYPE_NONE:
	default:
		break;
	}
}

void
Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet)
{
	set_previous_pos_setpoint(&pos_sp_triplet->current, &pos_sp_triplet->previous);

	if (is_current_onboard_mission_item_set(&pos_sp_triplet->current)) {
		/* try setting onboard mission item */
		_mission_type = MISSION_TYPE_ONBOARD;
		_loiter_set = false;

	} else if (is_current_offboard_mission_item_set(&pos_sp_triplet->current)) {
		/* try setting offboard mission item */
		_mission_type = MISSION_TYPE_OFFBOARD;
		_loiter_set = false;
	} else {
		_mission_type = MISSION_TYPE_NONE;
	}
}

void
Mission::set_previous_pos_setpoint(const struct position_setpoint_s *current_pos_sp,
		                   struct position_setpoint_s *previous_pos_sp)
{
	/* reuse current setpoint as previous setpoint */
	if (current_pos_sp->valid) {
		memcpy(previous_pos_sp, current_pos_sp, sizeof(struct position_setpoint_s));
	}
}

bool
Mission::is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
{
	if (_param_onboard_enabled.get() > 0
	    && _current_onboard_mission_index < (int)_onboard_mission.count) {
		struct mission_item_s new_mission_item;
		if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, true, &_current_onboard_mission_index,
					&new_mission_item)) {
			/* convert the current mission item and set it valid */
			mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
			current_pos_sp->valid = true;

			reset_mission_item_reached();

			/* TODO: report this somehow */
			memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
			return true;
		}
	}
	return false;
}

bool
Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
{
	if (_current_offboard_mission_index < (int)_offboard_mission.count) {
		dm_item_t dm_current;
		if (_offboard_mission.dataman_id == 0) {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
		} else {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
		}
		struct mission_item_s new_mission_item;
		if (read_mission_item(dm_current, true, &_current_offboard_mission_index, &new_mission_item)) {
			/* convert the current mission item and set it valid */
			mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
			current_pos_sp->valid = true;

			reset_mission_item_reached();

			report_current_offboard_mission_item();
			memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
			return true;
		} else {
			warnx("ERROR: WP read fail");
		}
	}
	return false;
}

void
Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp)
{
	int next_temp_mission_index = _onboard_mission.current_index + 1;

	/* try if there is a next onboard mission */
	if (next_temp_mission_index < (int)_onboard_mission.count) {
		struct mission_item_s new_mission_item;
		if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) {
			/* convert next mission item to position setpoint */
			mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
			next_pos_sp->valid = true;
			return;
		}
	}

	/* give up */
	next_pos_sp->valid = false;
	return;
}

void
Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp)
{
	/* try if there is a next offboard mission */
	int next_temp_mission_index = _offboard_mission.current_index + 1;
	if (next_temp_mission_index < (int)_offboard_mission.count) {
		dm_item_t dm_current;
		if (_offboard_mission.dataman_id == 0) {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
		} else {
			dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
		}
		struct mission_item_s new_mission_item;
		if (read_mission_item(dm_current, false, &next_temp_mission_index, &new_mission_item)) {
			/* convert next mission item to position setpoint */
			mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
			next_pos_sp->valid = true;
			return;
		}
	}
	/* give up */
	next_pos_sp->valid = false;
	return;
}

bool
Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index,
		           struct mission_item_s *new_mission_item)
{
	/* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */
	for (int i=0; i<10; i++) {
		const ssize_t len = sizeof(struct mission_item_s);

		/* read mission item from datamanager */
		if (dm_read(dm_item, *mission_index, new_mission_item, len) != len) {
			/* not supposed to happen unless the datamanager can't access the SD card, etc. */
			return false;
		}

		/* check for DO_JUMP item, and whether it hasn't not already been repeated enough times */
		if (new_mission_item->nav_cmd == NAV_CMD_DO_JUMP) {

			/* TODO: do this check more gracefully since it is not a serious error */
			if (new_mission_item->do_jump_current_count >= new_mission_item->do_jump_repeat_count) {
				return false;
			}

			/* only raise the repeat count if this is for the current mission item
			 * but not for the next mission item */
			if (is_current) {
				(new_mission_item->do_jump_current_count)++;

				/* save repeat count */
				if (dm_write(dm_item, *mission_index, DM_PERSIST_IN_FLIGHT_RESET,
					     new_mission_item, len) != len) {
					/* not supposed to happen unless the datamanager can't access the dataman */
					return false;
				}
				/* TODO: report about DO JUMP count */
			}
			/* set new mission item index and repeat
			 * we don't have to validate here, if it's invalid, we should realize this later .*/
			*mission_index = new_mission_item->do_jump_mission_index;

		} else {
			/* if it's not a DO_JUMP, then we were successful */
			return true;
		}
	}

	/* we have given up, we don't want to cycle forever */
	warnx("ERROR: cycling through mission items without success");
	return false;
}

void
Mission::report_mission_item_reached()
{
	if (_mission_type == MISSION_TYPE_OFFBOARD) {
		_mission_result.mission_reached = true;
		_mission_result.mission_index_reached = _current_offboard_mission_index;
	}
	publish_mission_result();
}

void
Mission::report_current_offboard_mission_item()
{
	_mission_result.index_current_mission = _current_offboard_mission_index;
	publish_mission_result();
}

void
Mission::publish_mission_result()
{
	/* lazily publish the mission result only once available */
	if (_mission_result_pub > 0) {
		/* publish mission result */
		orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);

	} else {
		/* advertise and publish */
		_mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
	}
	/* reset reached bool */
	_mission_result.mission_reached = false;
}