// i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
// i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
// i += put_uint8_t_by_index(version, i, msg->payload); // MAVLink version
boolidle;///< indicates if the system is following the waypoints or is waiting
uint16_tcurrent_active_wp_id;///< id of current waypoint
boolyawReached;///< boolean for yaw attitude reached
boolposReached;///< boolean for position reached
uint64_ttimestamp_lastoutside_orbit;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
uint64_ttimestamp_firstinside_orbit;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
std::vector<mavlink_mission_item_t*>waypoints1;///< vector1 that holds the waypoints
std::vector<mavlink_mission_item_t*>waypoints2;///< vector2 that holds the waypoints
std::vector<mavlink_mission_item_t*>*waypoints;///< pointer to the currently active waypoint vector
std::vector<mavlink_mission_item_t*>*waypoints_receive_buffer;///< pointer to the receive buffer waypoint vector