Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef MAVLINK_NO_DATA
00025 #define MAVLINK_NO_DATA
00026 #endif
00027
00028 #include <mavlink_types.h>
00029 extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t* buffer, uint16_t len);
00030
00031 #ifndef MAVLINK_SEND_UART_BYTES
00032 #define MAVLINK_SEND_UART_BYTES(chan, buffer, len) mavlink_send_uart_bytes(chan, buffer, len)
00033 #endif
00034 extern mavlink_system_t mavlink_system;
00035 #include <mavlink.h>
00036 #include <stdbool.h>
00037
00038
00039 enum MAVLINK_WPM_STATES
00040 {
00041 MAVLINK_WPM_STATE_IDLE = 0,
00042 MAVLINK_WPM_STATE_SENDLIST,
00043 MAVLINK_WPM_STATE_SENDLIST_SENDWPS,
00044 MAVLINK_WPM_STATE_GETLIST,
00045 MAVLINK_WPM_STATE_GETLIST_GETWPS,
00046 MAVLINK_WPM_STATE_GETLIST_GOTALL,
00047 MAVLINK_WPM_STATE_ENUM_END
00048 };
00049
00050 enum MAVLINK_WPM_CODES
00051 {
00052 MAVLINK_WPM_CODE_OK = 0,
00053 MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
00054 MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
00055 MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
00056 MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
00057 MAVLINK_WPM_CODE_ENUM_END
00058 };
00059
00060
00061
00062
00063 #define MAVLINK_WPM_MAX_WP_COUNT 15
00064 #define MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE ///< Enable double buffer and in-flight updates
00065 #ifndef MAVLINK_WPM_TEXT_FEEDBACK
00066 #define MAVLINK_WPM_TEXT_FEEDBACK 0 ///< Report back status information as text
00067 #endif
00068 #define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000 ///< Protocol communication timeout in milliseconds
00069 #define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000 ///< When to send a new setpoint
00070 #define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40
00071
00072
00073 struct mavlink_wpm_storage {
00074 mavlink_mission_item_t waypoints[MAVLINK_WPM_MAX_WP_COUNT];
00075 #ifdef MAVLINK_WPM_CONFIG_IN_FLIGHT_UPDATE
00076 mavlink_mission_item_t rcv_waypoints[MAVLINK_WPM_MAX_WP_COUNT];
00077 #endif
00078 uint16_t size;
00079 uint16_t max_size;
00080 uint16_t rcv_size;
00081 enum MAVLINK_WPM_STATES current_state;
00082 uint16_t current_wp_id;
00083 uint16_t current_active_wp_id;
00084 uint16_t current_count;
00085 uint8_t current_partner_sysid;
00086 uint8_t current_partner_compid;
00087 uint64_t timestamp_lastaction;
00088 uint64_t timestamp_last_send_setpoint;
00089 uint64_t timestamp_firstinside_orbit;
00090 uint64_t timestamp_lastoutside_orbit;
00091 uint32_t timeout;
00092 uint32_t delay_setpoint;
00093 float accept_range_yaw;
00094 float accept_range_distance;
00095 bool yaw_reached;
00096 bool pos_reached;
00097 bool idle;
00098 };
00099
00100 typedef struct mavlink_wpm_storage mavlink_wpm_storage;
00101
00102 void mavlink_wpm_init(mavlink_wpm_storage* state);
00103 void mavlink_wpm_loop();
00104 void mavlink_wpm_message_handler(const mavlink_message_t* msg);