Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_waypoint_count.h
00001 // MESSAGE WAYPOINT_COUNT PACKING 00002 00003 #define MAVLINK_MSG_ID_WAYPOINT_COUNT 44 00004 00005 typedef struct __mavlink_waypoint_count_t 00006 { 00007 uint8_t target_system; ///< System ID 00008 uint8_t target_component; ///< Component ID 00009 uint16_t count; ///< Number of Waypoints in the Sequence 00010 00011 } mavlink_waypoint_count_t; 00012 00013 00014 00015 /** 00016 * @brief Pack a waypoint_count message 00017 * @param system_id ID of this system 00018 * @param component_id ID of this component (e.g. 200 for IMU) 00019 * @param msg The MAVLink message to compress the data into 00020 * 00021 * @param target_system System ID 00022 * @param target_component Component ID 00023 * @param count Number of Waypoints in the Sequence 00024 * @return length of the message in bytes (excluding serial stream start sign) 00025 */ 00026 static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count) 00027 { 00028 uint16_t i = 0; 00029 msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; 00030 00031 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID 00032 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID 00033 i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence 00034 00035 return mavlink_finalize_message(msg, system_id, component_id, i); 00036 } 00037 00038 /** 00039 * @brief Pack a waypoint_count message 00040 * @param system_id ID of this system 00041 * @param component_id ID of this component (e.g. 200 for IMU) 00042 * @param chan The MAVLink channel this message was sent over 00043 * @param msg The MAVLink message to compress the data into 00044 * @param target_system System ID 00045 * @param target_component Component ID 00046 * @param count Number of Waypoints in the Sequence 00047 * @return length of the message in bytes (excluding serial stream start sign) 00048 */ 00049 static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t count) 00050 { 00051 uint16_t i = 0; 00052 msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; 00053 00054 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID 00055 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID 00056 i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence 00057 00058 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00059 } 00060 00061 /** 00062 * @brief Encode a waypoint_count struct into a message 00063 * 00064 * @param system_id ID of this system 00065 * @param component_id ID of this component (e.g. 200 for IMU) 00066 * @param msg The MAVLink message to compress the data into 00067 * @param waypoint_count C-struct to read the message contents from 00068 */ 00069 static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count) 00070 { 00071 return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count); 00072 } 00073 00074 /** 00075 * @brief Send a waypoint_count message 00076 * @param chan MAVLink channel to send the message 00077 * 00078 * @param target_system System ID 00079 * @param target_component Component ID 00080 * @param count Number of Waypoints in the Sequence 00081 */ 00082 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00083 00084 static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) 00085 { 00086 mavlink_message_t msg; 00087 mavlink_msg_waypoint_count_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, count); 00088 mavlink_send_uart(chan, &msg); 00089 } 00090 00091 #endif 00092 // MESSAGE WAYPOINT_COUNT UNPACKING 00093 00094 /** 00095 * @brief Get field target_system from waypoint_count message 00096 * 00097 * @return System ID 00098 */ 00099 static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg) 00100 { 00101 return (uint8_t)(msg->payload)[0]; 00102 } 00103 00104 /** 00105 * @brief Get field target_component from waypoint_count message 00106 * 00107 * @return Component ID 00108 */ 00109 static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg) 00110 { 00111 return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; 00112 } 00113 00114 /** 00115 * @brief Get field count from waypoint_count message 00116 * 00117 * @return Number of Waypoints in the Sequence 00118 */ 00119 static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg) 00120 { 00121 generic_16bit r; 00122 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00123 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; 00124 return (uint16_t)r.s; 00125 } 00126 00127 /** 00128 * @brief Decode a waypoint_count message into a struct 00129 * 00130 * @param msg The message to decode 00131 * @param waypoint_count C-struct to decode the message contents into 00132 */ 00133 static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count) 00134 { 00135 waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg); 00136 waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg); 00137 waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg); 00138 }
Generated on Tue Jul 12 2022 14:09:27 by 1.7.2