waypoints.c 41.9 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19
/*******************************************************************************
 
 Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch
 
 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/>.
 
 ****************************************************************************/

lm's avatar
lm committed
20
#include "waypoints.h"
LM's avatar
LM committed
21
#include <math.h>
22 23 24 25

bool debug = true;
bool verbose = true;

LM's avatar
LM committed
26 27
extern mavlink_wpm_storage wpm;

28 29 30
extern void mavlink_missionlib_send_message(mavlink_message_t* msg);
extern void mavlink_missionlib_send_gcs_string(const char* string);
extern uint64_t mavlink_missionlib_get_system_timestamp();
31 32 33
extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
		float param2, float param3, float param4, float param5_lat_x,
		float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
LM's avatar
LM committed
34 35 36


#define MAVLINK_WPM_NO_PRINTF
37

38
uint8_t mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
lm's avatar
lm committed
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
void mavlink_wpm_init(mavlink_wpm_storage* state)
{
	// Set all waypoints to zero
	
	// Set count to zero
	state->size = 0;
	state->max_size = MAVLINK_WPM_MAX_WP_COUNT;
	state->current_state = MAVLINK_WPM_STATE_IDLE;
	state->current_partner_sysid = 0;
	state->current_partner_compid = 0;
	state->timestamp_lastaction = 0;
	state->timestamp_last_send_setpoint = 0;
	state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT;
	state->delay_setpoint = MAVLINK_WPM_SETPOINT_DELAY_DEFAULT;
	state->idle = false;      				///< indicates if the system is following the waypoints or is waiting
	state->current_active_wp_id = -1;		///< id of current waypoint
	state->yaw_reached = false;						///< boolean for yaw attitude reached
	state->pos_reached = false;						///< boolean for position reached
	state->timestamp_lastoutside_orbit = 0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
	state->timestamp_firstinside_orbit = 0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
	
}

/*
 *  @brief Sends an waypoint ack message
 */
void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type)
{
    mavlink_message_t msg;
69
    mavlink_mission_ack_t wpa;
70 71 72 73 74
	
    wpa.target_system = wpm.current_partner_sysid;
    wpa.target_component = wpm.current_partner_compid;
    wpa.type = type;
	
75
    mavlink_msg_mission_ack_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpa);
76
    mavlink_missionlib_send_message(&msg);
77 78 79 80 81
	
    // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
	
    if (MAVLINK_WPM_TEXT_FEEDBACK)
	{
LM's avatar
LM committed
82
#ifdef MAVLINK_WPM_NO_PRINTF
83
    	mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
LM's avatar
LM committed
84 85 86
#else
		if (MAVLINK_WPM_VERBOSE) printf("Sent waypoint ack (%u) to ID %u\n", wpa.type, wpa.target_system);
#endif
87
		mavlink_missionlib_send_gcs_string("Sent waypoint ACK");
88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103
	}
}

/*
 *  @brief Broadcasts the new target waypoint and directs the MAV to fly there
 *
 *  This function broadcasts its new active waypoint sequence number and
 *  sends a message to the controller, advising it to fly to the coordinates
 *  of the waypoint with a given orientation
 *
 *  @param seq The waypoint sequence number the MAV should fly to.
 */
void mavlink_wpm_send_waypoint_current(uint16_t seq)
{
    if(seq < wpm.size)
    {
104
        mavlink_mission_item_t *cur = &(wpm.waypoints[seq]);
105 106
		
        mavlink_message_t msg;
107
        mavlink_mission_current_t wpc;
108 109 110
		
        wpc.seq = cur->seq;
		
111
        mavlink_msg_mission_current_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc);
112
        mavlink_missionlib_send_message(&msg);
113 114 115
		
        // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
		
116
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Set current waypoint\n"); //// printf("Broadcasted new current waypoint %u\n", wpc.seq);
117 118 119
    }
    else
    {
120
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds\n");
121 122 123 124 125 126 127 128 129 130 131 132 133
    }
}

/*
 *  @brief Directs the MAV to fly to a position
 *
 *  Sends a message to the controller, advising it to fly to the coordinates
 *  of the waypoint with a given orientation
 *
 *  @param seq The waypoint sequence number the MAV should fly to.
 */
void mavlink_wpm_send_setpoint(uint16_t seq)
{
134 135 136 137 138 139 140 141 142 143 144 145 146
    if(seq < wpm.size)
    {
        mavlink_mission_item_t *cur = &(wpm.waypoints[seq]);
        mavlink_missionlib_current_waypoint_changed(cur->seq, cur->param1,
        		cur->param2, cur->param3, cur->param4, cur->x,
        		cur->y, cur->z, cur->frame, cur->command);

        wpm.timestamp_last_send_setpoint = mavlink_missionlib_get_system_timestamp();
    }
    else
    {
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n"); //// if (verbose) // printf("ERROR: index out of bounds\n");
    }
147 148 149 150 151
}

void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count)
{
    mavlink_message_t msg;
152
    mavlink_mission_count_t wpc;
153 154 155 156 157
	
    wpc.target_system = wpm.current_partner_sysid;
    wpc.target_component = wpm.current_partner_compid;
    wpc.count = count;
	
158
    mavlink_msg_mission_count_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpc);
159
    mavlink_missionlib_send_message(&msg);
160
	
161
    if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint count"); //// if (verbose) // printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system);
162 163 164 165 166 167 168 169 170
	
    // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}

void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
{
    if (seq < wpm.size)
    {
        mavlink_message_t msg;
171
        mavlink_mission_item_t *wp = &(wpm.waypoints[seq]);
172 173
        wp->target_system = wpm.current_partner_sysid;
        wp->target_component = wpm.current_partner_compid;
174
        mavlink_msg_mission_item_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, wp);
175 176
        mavlink_missionlib_send_message(&msg);
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint"); //// if (verbose) // printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system);
177 178 179 180 181
		
        // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
    }
    else
    {
182
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index out of bounds\n");
183 184 185 186 187 188 189 190
    }
}

void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq)
{
    if (seq < wpm.max_size)
    {
        mavlink_message_t msg;
191
        mavlink_mission_request_t wpr;
192 193 194
        wpr.target_system = wpm.current_partner_sysid;
        wpr.target_component = wpm.current_partner_compid;
        wpr.seq = seq;
195
        mavlink_msg_mission_request_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wpr);
196 197
        mavlink_missionlib_send_message(&msg);
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint request"); //// if (verbose) // printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system);
198 199 200 201 202
		
        // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
    }
    else
    {
203
        if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity\n");
204 205 206 207 208 209 210 211 212 213 214 215 216
    }
}

/*
 *  @brief emits a message that a waypoint reached
 *
 *  This function broadcasts a message that a waypoint is reached.
 *
 *  @param seq The waypoint sequence number the MAV has reached.
 */
void mavlink_wpm_send_waypoint_reached(uint16_t seq)
{
    mavlink_message_t msg;
217
    mavlink_mission_item_reached_t wp_reached;
218 219 220
	
    wp_reached.seq = seq;
	
221
    mavlink_msg_mission_item_reached_encode(mavlink_system.sysid, mavlink_wpm_comp_id, &msg, &wp_reached);
222
    mavlink_missionlib_send_message(&msg);
223
	
224
    if (MAVLINK_WPM_TEXT_FEEDBACK) mavlink_missionlib_send_gcs_string("Sent waypoint reached message"); //// if (verbose) // printf("Sent waypoint %u reached message\n", wp_reached.seq);
225 226 227 228 229 230 231 232
	
    // FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}

//float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z)
//{
//    if (seq < wpm.size)
//    {
233
//        mavlink_mission_item_t *cur = waypoints->at(seq);
234 235 236 237 238 239 240
//		
//        const PxVector3 A(cur->x, cur->y, cur->z);
//        const PxVector3 C(x, y, z);
//		
//        // seq not the second last waypoint
//        if ((uint16_t)(seq+1) < wpm.size)
//        {
241
//            mavlink_mission_item_t *next = waypoints->at(seq+1);
242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264
//            const PxVector3 B(next->x, next->y, next->z);
//            const float r = (B-A).dot(C-A) / (B-A).lengthSquared();
//            if (r >= 0 && r <= 1)
//            {
//                const PxVector3 P(A + r*(B-A));
//                return (P-C).length();
//            }
//            else if (r < 0.f)
//            {
//                return (C-A).length();
//            }
//            else
//            {
//                return (C-B).length();
//            }
//        }
//        else
//        {
//            return (C-A).length();
//        }
//    }
//    else
//    {
LM's avatar
LM committed
265
//        // if (verbose) // printf("ERROR: index out of bounds\n");
266 267 268 269 270 271 272 273
//    }
//    return -1.f;
//}

float mavlink_wpm_distance_to_point(uint16_t seq, float x, float y, float z)
{
//    if (seq < wpm.size)
//    {
274
//        mavlink_mission_item_t *cur = waypoints->at(seq);
275 276 277 278 279 280 281 282
//		
//        const PxVector3 A(cur->x, cur->y, cur->z);
//        const PxVector3 C(x, y, z);
//		
//        return (C-A).length();
//    }
//    else
//    {
LM's avatar
LM committed
283
//        // if (verbose) // printf("ERROR: index out of bounds\n");
284 285 286 287
//    }
    return -1.f;
}

LM's avatar
LM committed
288
void mavlink_wpm_loop()
289 290
{
    //check for timed-out operations
291
    uint64_t now = mavlink_missionlib_get_system_timestamp();
292 293
    if (now-wpm.timestamp_lastaction > wpm.timeout && wpm.current_state != MAVLINK_WPM_STATE_IDLE)
    {
LM's avatar
LM committed
294
#ifdef MAVLINK_WPM_NO_PRINTF
295
    	mavlink_missionlib_send_gcs_string("Operation timeout switching -> IDLE");
LM's avatar
LM committed
296 297 298 299
#else
		if (MAVLINK_WPM_VERBOSE) printf("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_state);
#endif
		wpm.current_state = MAVLINK_WPM_STATE_IDLE;
300 301 302 303 304 305 306 307 308 309 310 311 312 313 314
        wpm.current_count = 0;
        wpm.current_partner_sysid = 0;
        wpm.current_partner_compid = 0;
        wpm.current_wp_id = -1;
		
        if(wpm.size == 0)
        {
            wpm.current_active_wp_id = -1;
        }
    }
	
    if(now-wpm.timestamp_last_send_setpoint > wpm.delay_setpoint && wpm.current_active_wp_id < wpm.size)
    {
        mavlink_wpm_send_setpoint(wpm.current_active_wp_id);
    }
LM's avatar
LM committed
315 316 317 318 319
}

void mavlink_wpm_message_handler(const mavlink_message_t* msg)
{
	uint64_t now = mavlink_missionlib_get_system_timestamp();
320 321 322 323 324 325
    switch(msg->msgid)
    {
		case MAVLINK_MSG_ID_ATTITUDE:
        {
            if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size)
            {
326
                mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]);
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
                if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED)
                {
                    mavlink_attitude_t att;
                    mavlink_msg_attitude_decode(msg, &att);
                    float yaw_tolerance = wpm.accept_range_yaw;
                    //compare current yaw
                    if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI)
                    {
                        if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4)
                            wpm.yaw_reached = true;
                    }
                    else if(att.yaw - yaw_tolerance < 0.0f)
                    {
                        float lowerBound = 360.0f + att.yaw - yaw_tolerance;
                        if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance)
                            wpm.yaw_reached = true;
                    }
                    else
                    {
                        float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI;
                        if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound)
                            wpm.yaw_reached = true;
                    }
                }
            }
            break;
        }
			
355
		case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
356 357 358
        {
            if(msg->sysid == mavlink_system.sysid && wpm.current_active_wp_id < wpm.size)
            {
359
                mavlink_mission_item_t *wp = &(wpm.waypoints[wpm.current_active_wp_id]);
360 361 362
				
                if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED)
                {
363 364
                    mavlink_local_position_ned_t pos;
                    mavlink_msg_local_position_ned_decode(msg, &pos);
LM's avatar
LM committed
365
                    //// if (debug) // printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z);
366 367 368 369 370 371 372
					
                    wpm.pos_reached = false;
					
                    // compare current position (given in message) with current waypoint
                    float orbit = wp->param1;
					
                    float dist;
LM's avatar
LM committed
373 374 375 376 377 378 379
//                    if (wp->param2 == 0)
//                    {
//						// FIXME segment distance
//                        //dist = mavlink_wpm_distance_to_segment(current_active_wp_id, pos.x, pos.y, pos.z);
//                    }
//                    else
//                    {
380
                        dist = mavlink_wpm_distance_to_point(wpm.current_active_wp_id, pos.x, pos.y, pos.z);
LM's avatar
LM committed
381
//                    }
382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397
					
                    if (dist >= 0.f && dist <= orbit && wpm.yaw_reached)
                    {
                        wpm.pos_reached = true;
                    }
                }
            }
            break;
        }
			
//		case MAVLINK_MSG_ID_CMD: // special action from ground station
//        {
//            mavlink_cmd_t action;
//            mavlink_msg_cmd_decode(msg, &action);
//            if(action.target == mavlink_system.sysid)
//            {
LM's avatar
LM committed
398
//                // if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl;
399 400 401
//                switch (action.action)
//                {
//						//				case MAV_ACTION_LAUNCH:
LM's avatar
LM committed
402
//						//					// if (verbose) std::cerr << "Launch received" << std::endl;
403 404 405 406 407 408
//						//					current_active_wp_id = 0;
//						//					if (wpm.size>0)
//						//					{
//						//						setActive(waypoints[current_active_wp_id]);
//						//					}
//						//					else
LM's avatar
LM committed
409
//						//						// if (verbose) std::cerr << "No launch, waypointList empty" << std::endl;
410 411 412
//						//					break;
//						
//						//				case MAV_ACTION_CONTINUE:
LM's avatar
LM committed
413
//						//					// if (verbose) std::c
414 415 416 417 418 419
//						//					err << "Continue received" << std::endl;
//						//					idle = false;
//						//					setActive(waypoints[current_active_wp_id]);
//						//					break;
//						
//						//				case MAV_ACTION_HALT:
LM's avatar
LM committed
420
//						//					// if (verbose) std::cerr << "Halt received" << std::endl;
421 422 423 424
//						//					idle = true;
//						//					break;
//						
//						//				default:
LM's avatar
LM committed
425
//						//					// if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl;
426 427 428 429 430 431
//						//					break;
//                }
//            }
//            break;
//        }
			
432
		case MAVLINK_MSG_ID_MISSION_ACK:
433
        {
434 435
            mavlink_mission_ack_t wpa;
            mavlink_msg_mission_ack_decode(msg, &wpa);
436
			
lm's avatar
lm committed
437
            if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/))
438 439 440 441 442 443 444
            {
                wpm.timestamp_lastaction = now;
				
                if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS)
                {
                    if (wpm.current_wp_id == wpm.size-1)
                    {
LM's avatar
LM committed
445
#ifdef MAVLINK_WPM_NO_PRINTF
446
    	mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
LM's avatar
LM committed
447 448 449 450
#else
		if (MAVLINK_WPM_VERBOSE) printf("Received ACK after having sent last waypoint, going to state MAVLINK_WPM_STATE_IDLE\n");
#endif
						wpm.current_state = MAVLINK_WPM_STATE_IDLE;
451 452 453 454 455 456
                        wpm.current_wp_id = 0;
                    }
                }
            }
			else
			{
LM's avatar
LM committed
457
#ifdef MAVLINK_WPM_NO_PRINTF
458
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
LM's avatar
LM committed
459 460 461
#else
		if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
#endif
462 463 464 465
			}
            break;
        }
			
466
		case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
467
        {
468 469
            mavlink_mission_set_current_t wpc;
            mavlink_msg_mission_set_current_decode(msg, &wpc);
470
			
lm's avatar
lm committed
471
            if(wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/)
472 473 474 475 476 477 478
            {
                wpm.timestamp_lastaction = now;
				
                if (wpm.current_state == MAVLINK_WPM_STATE_IDLE)
                {
                    if (wpc.seq < wpm.size)
                    {
479
                        // if (verbose) // printf("Received MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT\n");
480 481 482 483 484 485 486 487 488 489 490 491 492
                        wpm.current_active_wp_id = wpc.seq;
                        uint32_t i;
                        for(i = 0; i < wpm.size; i++)
                        {
                            if (i == wpm.current_active_wp_id)
                            {
                                wpm.waypoints[i].current = true;
                            }
                            else
                            {
                                wpm.waypoints[i].current = false;
                            }
                        }
LM's avatar
LM committed
493
#ifdef MAVLINK_WPM_NO_PRINTF
494
    	mavlink_missionlib_send_gcs_string("NEW WP SET");
LM's avatar
LM committed
495 496 497
#else
		if (MAVLINK_WPM_VERBOSE) printf("New current waypoint %u\n", wpm.current_active_wp_id);
#endif
498 499 500 501 502 503 504 505
                        wpm.yaw_reached = false;
                        wpm.pos_reached = false;
                        mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id);
                        mavlink_wpm_send_setpoint(wpm.current_active_wp_id);
                        wpm.timestamp_firstinside_orbit = 0;
                    }
                    else
                    {
LM's avatar
LM committed
506
#ifdef MAVLINK_WPM_NO_PRINTF
507
    	mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
LM's avatar
LM committed
508
#else
509
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT: Index out of bounds\n");
LM's avatar
LM committed
510
#endif
511 512 513 514
                    }
                }
				else
				{
LM's avatar
LM committed
515
#ifdef MAVLINK_WPM_NO_PRINTF
516
    	mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
LM's avatar
LM committed
517 518 519
#else
		if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE NOT IN IDLE STATE\n");
#endif
520 521 522 523
				}
            }
			else
			{
LM's avatar
LM committed
524
#ifdef MAVLINK_WPM_NO_PRINTF
525
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
LM's avatar
LM committed
526 527 528
#else
		if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
#endif
529 530 531 532
			}
            break;
        }
			
533
		case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
534
        {
535 536
            mavlink_mission_request_list_t wprl;
            mavlink_msg_mission_request_list_decode(msg, &wprl);
lm's avatar
lm committed
537
            if(wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/)
538 539 540 541 542 543 544
            {
                wpm.timestamp_lastaction = now;
				
                if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST)
                {
                    if (wpm.size > 0)
                    {
545 546
                        //if (verbose && wpm.current_state == MAVLINK_WPM_STATE_IDLE) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
//                        if (verbose && wpm.current_state == MAVLINK_WPM_STATE_SENDLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
547 548 549 550 551 552 553
                        wpm.current_state = MAVLINK_WPM_STATE_SENDLIST;
                        wpm.current_wp_id = 0;
                        wpm.current_partner_sysid = msg->sysid;
                        wpm.current_partner_compid = msg->compid;
                    }
                    else
                    {
554
                        // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid);
555 556 557 558 559 560
                    }
                    wpm.current_count = wpm.size;
                    mavlink_wpm_send_waypoint_count(msg->sysid,msg->compid, wpm.current_count);
                }
                else
                {
561
                    // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).\n", wpm.current_state);
562 563 564 565
                }
            }
			else
			{
LM's avatar
LM committed
566
				// if (verbose) // printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT MISMATCH\n");
567 568 569 570 571
			}

            break;
        }
			
572
		case MAVLINK_MSG_ID_MISSION_REQUEST:
573
        {
574 575
            mavlink_mission_request_t wpr;
            mavlink_msg_mission_request_decode(msg, &wpr);
lm's avatar
lm committed
576
            if(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/)
577 578 579 580 581 582
            {
                wpm.timestamp_lastaction = now;
				
                //ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint)
                if ((wpm.current_state == MAVLINK_WPM_STATE_SENDLIST && wpr.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && (wpr.seq == wpm.current_wp_id || wpr.seq == wpm.current_wp_id + 1) && wpr.seq < wpm.size))
                {
LM's avatar
LM committed
583 584 585
                    if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST)
                    {
#ifdef MAVLINK_WPM_NO_PRINTF
586
    	mavlink_missionlib_send_gcs_string("GOT WP REQ, state -> SEND");
LM's avatar
LM committed
587
#else
588
		if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
LM's avatar
LM committed
589 590 591 592 593
#endif
                    }
                    if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id + 1)
                    {
#ifdef MAVLINK_WPM_NO_PRINTF
594
    	mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ");
LM's avatar
LM committed
595
#else
596
		if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
LM's avatar
LM committed
597 598 599 600 601
#endif
                    }
                    if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS && wpr.seq == wpm.current_wp_id)
                    {
#ifdef MAVLINK_WPM_NO_PRINTF
602
    	mavlink_missionlib_send_gcs_string("GOT 2nd WP REQ");
LM's avatar
LM committed
603
#else
604
		if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n", wpr.seq, msg->sysid);
LM's avatar
LM committed
605 606
#endif
                    }
607 608 609 610 611 612 613
					
                    wpm.current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
                    wpm.current_wp_id = wpr.seq;
                    mavlink_wpm_send_waypoint(wpm.current_partner_sysid, wpm.current_partner_compid, wpr.seq);
                }
                else
                {
LM's avatar
LM committed
614
                    // if (verbose)
615
                    {
LM's avatar
LM committed
616 617 618
                        if (!(wpm.current_state == MAVLINK_WPM_STATE_SENDLIST || wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS))
						{
#ifdef MAVLINK_WPM_NO_PRINTF
619
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
LM's avatar
LM committed
620
#else
621
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).\n", wpm.current_state);
LM's avatar
LM committed
622 623 624
#endif
		break;
						}
625 626
                        else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST)
                        {
LM's avatar
LM committed
627 628 629
                            if (wpr.seq != 0)
							{
#ifdef MAVLINK_WPM_NO_PRINTF
630
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
LM's avatar
LM committed
631
#else
632
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the first requested waypoint ID (%u) was not 0.\n", wpr.seq);
LM's avatar
LM committed
633 634
#endif
							}
635 636 637
                        }
                        else if (wpm.current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS)
                        {
LM's avatar
LM committed
638 639 640
                            if (wpr.seq != wpm.current_wp_id && wpr.seq != wpm.current_wp_id + 1)
							{
#ifdef MAVLINK_WPM_NO_PRINTF
641
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
LM's avatar
LM committed
642
#else
643
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n", wpr.seq, wpm.current_wp_id, wpm.current_wp_id+1);
LM's avatar
LM committed
644 645 646 647 648
#endif
							}
							else if (wpr.seq >= wpm.size)
							{
#ifdef MAVLINK_WPM_NO_PRINTF
649
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
LM's avatar
LM committed
650
#else
651
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.\n", wpr.seq);
LM's avatar
LM committed
652 653
#endif
							}
654
                        }
LM's avatar
LM committed
655 656 657
                        else
						{
#ifdef MAVLINK_WPM_NO_PRINTF
658
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?");
LM's avatar
LM committed
659
#else
660
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST - FIXME: missed error description\n");
LM's avatar
LM committed
661 662
#endif
						}
663 664 665 666 667 668
                    }
                }
            }
            else
            {
                //we we're target but already communicating with someone else
lm's avatar
lm committed
669
                if((wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid))
670
                {
LM's avatar
LM committed
671
#ifdef MAVLINK_WPM_NO_PRINTF
672
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
LM's avatar
LM committed
673
#else
674
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.\n", msg->sysid, wpm.current_partner_sysid);
LM's avatar
LM committed
675
#endif
676 677 678
                }
				else
				{
LM's avatar
LM committed
679
#ifdef MAVLINK_WPM_NO_PRINTF
680
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
LM's avatar
LM committed
681 682 683
#else
		if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
#endif
684 685 686 687 688 689
				}

            }
            break;
        }
			
690
		case MAVLINK_MSG_ID_MISSION_COUNT:
691
        {
692 693
            mavlink_mission_count_t wpc;
            mavlink_msg_mission_count_decode(msg, &wpc);
lm's avatar
lm committed
694
            if(wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/)
695 696 697 698 699 700 701
            {
                wpm.timestamp_lastaction = now;
				
                if (wpm.current_state == MAVLINK_WPM_STATE_IDLE || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id == 0))
                {
                    if (wpc.count > 0)
                    {
LM's avatar
LM committed
702 703 704
                        if (wpm.current_state == MAVLINK_WPM_STATE_IDLE)
                        {
#ifdef MAVLINK_WPM_NO_PRINTF
705
    	mavlink_missionlib_send_gcs_string("WP CMD OK: state -> GETLIST");
LM's avatar
LM committed
706
#else
707
		if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST\n", wpc.count, msg->sysid);
LM's avatar
LM committed
708 709 710 711 712
#endif
                        }
                        if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST)
                        {
#ifdef MAVLINK_WPM_NO_PRINTF
713
    	mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
LM's avatar
LM committed
714
#else
715
		if (MAVLINK_WPM_VERBOSE) printf("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u\n", wpc.count, msg->sysid);
LM's avatar
LM committed
716 717
#endif
                        }
718 719 720 721 722 723 724
						
                        wpm.current_state = MAVLINK_WPM_STATE_GETLIST;
                        wpm.current_wp_id = 0;
                        wpm.current_partner_sysid = msg->sysid;
                        wpm.current_partner_compid = msg->compid;
                        wpm.current_count = wpc.count;
						
LM's avatar
LM committed
725
#ifdef MAVLINK_WPM_NO_PRINTF
726
    	mavlink_missionlib_send_gcs_string("CLR RCV BUF: READY");
LM's avatar
LM committed
727 728 729
#else
		if (MAVLINK_WPM_VERBOSE) printf("clearing receive buffer and readying for receiving waypoints\n");
#endif
730 731 732 733 734 735 736 737 738 739 740
						wpm.rcv_size = 0;
                        //while(waypoints_receive_buffer->size() > 0)
//                        {
//                            delete waypoints_receive_buffer->back();
//                            waypoints_receive_buffer->pop_back();
//                        }
						
                        mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id);
                    }
                    else if (wpc.count == 0)
                    {
LM's avatar
LM committed
741
#ifdef MAVLINK_WPM_NO_PRINTF
742
    	mavlink_missionlib_send_gcs_string("COUNT 0");
LM's avatar
LM committed
743 744 745
#else
		if (MAVLINK_WPM_VERBOSE) printf("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE\n");
#endif
746 747 748 749 750 751 752 753 754 755 756 757 758 759
						wpm.rcv_size = 0;
                        //while(waypoints_receive_buffer->size() > 0)
//                        {
//                            delete waypoints->back();
//                            waypoints->pop_back();
//                        }
                        wpm.current_active_wp_id = -1;
                        wpm.yaw_reached = false;
                        wpm.pos_reached = false;
                        break;
						
                    }
                    else
                    {
LM's avatar
LM committed
760
#ifdef MAVLINK_WPM_NO_PRINTF
761
    	mavlink_missionlib_send_gcs_string("IGN WP CMD");
LM's avatar
LM committed
762
#else
763
		if (MAVLINK_WPM_VERBOSE) printf("Ignoring MAVLINK_MSG_ID_MISSION_ITEM_COUNT from %u with count of %u\n", msg->sysid, wpc.count);
LM's avatar
LM committed
764
#endif
765 766 767 768
                    }
                }
                else
                {
LM's avatar
LM committed
769 770 771
                    if (!(wpm.current_state == MAVLINK_WPM_STATE_IDLE || wpm.current_state == MAVLINK_WPM_STATE_GETLIST))
					{
#ifdef MAVLINK_WPM_NO_PRINTF
772
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
LM's avatar
LM committed
773
#else
774
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm doing something else already (state=%i).\n", wpm.current_state);
LM's avatar
LM committed
775 776 777 778 779
#endif
					}
                    else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wpm.current_wp_id != 0)
					{
#ifdef MAVLINK_WPM_NO_PRINTF
780
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
LM's avatar
LM committed
781
#else
782
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.\n", wpm.current_wp_id);
LM's avatar
LM committed
783 784 785 786 787
#endif
					}
                    else
					{
#ifdef MAVLINK_WPM_NO_PRINTF
788
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: ?");
LM's avatar
LM committed
789
#else
790
		if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT - FIXME: missed error description\n");
LM's avatar
LM committed
791 792
#endif
					}
793 794 795 796
                }
            }
			else
			{
LM's avatar
LM committed
797
#ifdef MAVLINK_WPM_NO_PRINTF
798
    	mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
LM's avatar
LM committed
799 800 801
#else
		if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
#endif
802 803 804 805 806
			}
            
        }
			break;
			
807
		case MAVLINK_MSG_ID_MISSION_ITEM:
808
        {
809 810
            mavlink_mission_item_t wp;
            mavlink_msg_mission_item_decode(msg, &wp);
811
			
812
			mavlink_missionlib_send_gcs_string("GOT WP");
813
			
lm's avatar
lm committed
814
            if((msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && (wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/))
815 816 817 818 819 820
            {
                wpm.timestamp_lastaction = now;
				
                //ensure that we are in the correct state and that the first waypoint has id 0 and the following waypoints have the correct ids
                if ((wpm.current_state == MAVLINK_WPM_STATE_GETLIST && wp.seq == 0) || (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id && wp.seq < wpm.current_count))
                {
821 822 823
//                    if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid);
//                    if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u from %u\n", wp.seq, msg->sysid);
//                    if (verbose && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS && wp.seq-1 == wpm.current_wp_id) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM %u (again) from %u\n", wp.seq, msg->sysid);
lm's avatar
lm committed
824
//					
825
                    wpm.current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS;
826 827
                    mavlink_mission_item_t* newwp = &(wpm.rcv_waypoints[wp.seq]);
                    memcpy(newwp, &wp, sizeof(mavlink_mission_item_t));
lm's avatar
lm committed
828
					wpm.current_wp_id = wp.seq + 1;
829
					
LM's avatar
LM committed
830
                    // if (verbose) // printf ("Added new waypoint to list. X= %f\t Y= %f\t Z= %f\t Yaw= %f\n", newwp->x, newwp->y, newwp->z, newwp->param4);
831 832 833
					
                    if(wpm.current_wp_id == wpm.current_count && wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)
                    {
834
						mavlink_missionlib_send_gcs_string("GOT ALL WPS");
LM's avatar
LM committed
835
                        // if (verbose) // printf("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE\n", wpm.current_count);
836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858
						
                        mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0);
						
                        if (wpm.current_active_wp_id > wpm.rcv_size-1)
                        {
                            wpm.current_active_wp_id = wpm.rcv_size-1;
                        }
						
                        // switch the waypoints list
						// FIXME CHECK!!!
						for (int i = 0; i < wpm.current_count; ++i)
						{
							wpm.waypoints[i] = wpm.rcv_waypoints[i];
						}
						wpm.size = wpm.current_count;
						
                        //get the new current waypoint
                        uint32_t i;
                        for(i = 0; i < wpm.size; i++)
                        {
                            if (wpm.waypoints[i].current == 1)
                            {
                                wpm.current_active_wp_id = i;
LM's avatar
LM committed
859
                                //// if (verbose) // printf("New current waypoint %u\n", current_active_wp_id);
860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889
                                wpm.yaw_reached = false;
                                wpm.pos_reached = false;
								mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id);
                                mavlink_wpm_send_setpoint(wpm.current_active_wp_id);
								wpm.timestamp_firstinside_orbit = 0;
                                break;
                            }
                        }
						
                        if (i == wpm.size)
                        {
                            wpm.current_active_wp_id = -1;
                            wpm.yaw_reached = false;
                            wpm.pos_reached = false;
                            wpm.timestamp_firstinside_orbit = 0;
                        }
						
                        wpm.current_state = MAVLINK_WPM_STATE_IDLE;
                    }
                    else
                    {
                        mavlink_wpm_send_waypoint_request(wpm.current_partner_sysid, wpm.current_partner_compid, wpm.current_wp_id);
                    }
                }
                else
                {
                    if (wpm.current_state == MAVLINK_WPM_STATE_IDLE)
                    {
                        //we're done receiving waypoints, answer with ack.
                        mavlink_wpm_send_waypoint_ack(wpm.current_partner_sysid, wpm.current_partner_compid, 0);
890
                        // printf("Received MAVLINK_MSG_ID_MISSION_ITEM while state=MAVLINK_WPM_STATE_IDLE, answered with WAYPOINT_ACK.\n");
891
                    }
LM's avatar
LM committed
892
                    // if (verbose)
893
                    {
LM's avatar
LM committed
894 895
                        if (!(wpm.current_state == MAVLINK_WPM_STATE_GETLIST || wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS))
						{
896
							// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u because i'm doing something else already (state=%i).\n", wp.seq, wpm.current_state);
LM's avatar
LM committed
897 898
							break;
						}
899 900
                        else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST)
                        {
LM's avatar
LM committed
901 902
                            if(!(wp.seq == 0))
							{
903
								// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.\n", wp.seq);
LM's avatar
LM committed
904 905 906
							}
                            else
							{
907
								// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
LM's avatar
LM committed
908
							}
909 910 911
                        }
                        else if (wpm.current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS)
                        {
LM's avatar
LM committed
912 913
                            if (!(wp.seq == wpm.current_wp_id))
							{
914
								// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.\n", wp.seq, wpm.current_wp_id);
LM's avatar
LM committed
915 916 917
							}
                            else if (!(wp.seq < wpm.current_count))
							{
918
								// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.\n", wp.seq);
LM's avatar
LM committed
919 920 921
							}
                            else
							{
922
								// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
LM's avatar
LM committed
923
							}
924
                        }
LM's avatar
LM committed
925 926
                        else
						{
927
							// printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u - FIXME: missed error description\n", wp.seq);
LM's avatar
LM committed
928
						}
929 930 931 932 933 934
                    }
                }
            }
            else
            {
                //we we're target but already communicating with someone else
lm's avatar
lm committed
935
                if((wp.target_system == mavlink_system.sysid /*&& wp.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == wpm.current_partner_sysid && msg->compid == wpm.current_partner_compid) && wpm.current_state != MAVLINK_WPM_STATE_IDLE)
936
                {
937
                    // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid);
938
                }
lm's avatar
lm committed
939
                else if(wp.target_system == mavlink_system.sysid /* && wp.target_component == mavlink_wpm_comp_id*/)
940
                {
941
                    // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM %u from ID %u because i have no idea what to do with it\n", wp.seq, msg->sysid);
942 943 944 945 946
                }
            }
            break;
        }
			
947
		case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
948
        {
949 950
            mavlink_mission_clear_all_t wpca;
            mavlink_msg_mission_clear_all_decode(msg, &wpca);
951
			
lm's avatar
lm committed
952
            if(wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state == MAVLINK_WPM_STATE_IDLE)
953 954 955
            {
                wpm.timestamp_lastaction = now;
				
956
                // if (verbose) // printf("Got MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u deleting all waypoints\n", msg->sysid);
957 958 959 960 961 962
                // Delete all waypoints
				wpm.size = 0;
                wpm.current_active_wp_id = -1;
                wpm.yaw_reached = false;
                wpm.pos_reached = false;
            }
lm's avatar
lm committed
963
            else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && wpm.current_state != MAVLINK_WPM_STATE_IDLE)
964
            {
965
                // if (verbose) // printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_CLEAR_LIST from %u because i'm doing something else already (state=%i).\n", msg->sysid, wpm.current_state);
966 967 968 969 970 971
            }
            break;
        }
			
		default:
        {
LM's avatar
LM committed
972
            // if (debug) // printf("Waypoint: received message of unknown type");
973 974 975 976 977 978 979 980 981
            break;
        }
    }
	
    //check if the current waypoint was reached
    if (wpm.pos_reached /*wpm.yaw_reached &&*/ && !wpm.idle)
    {
        if (wpm.current_active_wp_id < wpm.size)
        {
982
            mavlink_mission_item_t *cur_wp = &(wpm.waypoints[wpm.current_active_wp_id]);
983 984 985 986
			
            if (wpm.timestamp_firstinside_orbit == 0)
            {
                // Announce that last waypoint was reached
LM's avatar
LM committed
987
                // if (verbose) // printf("*** Reached waypoint %u ***\n", cur_wp->seq);
988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017
                mavlink_wpm_send_waypoint_reached(cur_wp->seq);
                wpm.timestamp_firstinside_orbit = now;
            }
			
            // check if the MAV was long enough inside the waypoint orbit
            //if (now-timestamp_lastoutside_orbit > (cur_wp->hold_time*1000))
            if(now-wpm.timestamp_firstinside_orbit >= cur_wp->param2*1000)
            {
                if (cur_wp->autocontinue)
                {
                    cur_wp->current = 0;
                    if (wpm.current_active_wp_id == wpm.size - 1 && wpm.size > 1)
                    {
                        //the last waypoint was reached, if auto continue is
                        //activated restart the waypoint list from the beginning
                        wpm.current_active_wp_id = 1;
                    }
                    else
                    {
                        if ((uint16_t)(wpm.current_active_wp_id + 1) < wpm.size)
                            wpm.current_active_wp_id++;
                    }
					
                    // Fly to next waypoint
                    wpm.timestamp_firstinside_orbit = 0;
                    mavlink_wpm_send_waypoint_current(wpm.current_active_wp_id);
                    mavlink_wpm_send_setpoint(wpm.current_active_wp_id);
                    wpm.waypoints[wpm.current_active_wp_id].current = true;
                    wpm.pos_reached = false;
                    wpm.yaw_reached = false;
LM's avatar
LM committed
1018
                    // if (verbose) // printf("Set new waypoint (%u)\n", wpm.current_active_wp_id);
1019 1020 1021 1022 1023 1024 1025 1026 1027 1028
                }
            }
        }
    }
    else
    {
        wpm.timestamp_lastoutside_orbit = now;
    }
}