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_gps_set_global_origin.h
00001 // MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING 00002 00003 #define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48 00004 00005 typedef struct __mavlink_gps_set_global_origin_t 00006 { 00007 uint8_t target_system; ///< System ID 00008 uint8_t target_component; ///< Component ID 00009 int32_t latitude; ///< global position * 1E7 00010 int32_t longitude; ///< global position * 1E7 00011 int32_t altitude; ///< global position * 1000 00012 00013 } mavlink_gps_set_global_origin_t; 00014 00015 00016 00017 /** 00018 * @brief Pack a gps_set_global_origin message 00019 * @param system_id ID of this system 00020 * @param component_id ID of this component (e.g. 200 for IMU) 00021 * @param msg The MAVLink message to compress the data into 00022 * 00023 * @param target_system System ID 00024 * @param target_component Component ID 00025 * @param latitude global position * 1E7 00026 * @param longitude global position * 1E7 00027 * @param altitude global position * 1000 00028 * @return length of the message in bytes (excluding serial stream start sign) 00029 */ 00030 static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) 00031 { 00032 uint16_t i = 0; 00033 msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; 00034 00035 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID 00036 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID 00037 i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7 00038 i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7 00039 i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000 00040 00041 return mavlink_finalize_message(msg, system_id, component_id, i); 00042 } 00043 00044 /** 00045 * @brief Pack a gps_set_global_origin message 00046 * @param system_id ID of this system 00047 * @param component_id ID of this component (e.g. 200 for IMU) 00048 * @param chan The MAVLink channel this message was sent over 00049 * @param msg The MAVLink message to compress the data into 00050 * @param target_system System ID 00051 * @param target_component Component ID 00052 * @param latitude global position * 1E7 00053 * @param longitude global position * 1E7 00054 * @param altitude global position * 1000 00055 * @return length of the message in bytes (excluding serial stream start sign) 00056 */ 00057 static inline uint16_t mavlink_msg_gps_set_global_origin_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, int32_t latitude, int32_t longitude, int32_t altitude) 00058 { 00059 uint16_t i = 0; 00060 msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; 00061 00062 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID 00063 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID 00064 i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7 00065 i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7 00066 i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000 00067 00068 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00069 } 00070 00071 /** 00072 * @brief Encode a gps_set_global_origin struct into a message 00073 * 00074 * @param system_id ID of this system 00075 * @param component_id ID of this component (e.g. 200 for IMU) 00076 * @param msg The MAVLink message to compress the data into 00077 * @param gps_set_global_origin C-struct to read the message contents from 00078 */ 00079 static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin) 00080 { 00081 return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude); 00082 } 00083 00084 /** 00085 * @brief Send a gps_set_global_origin message 00086 * @param chan MAVLink channel to send the message 00087 * 00088 * @param target_system System ID 00089 * @param target_component Component ID 00090 * @param latitude global position * 1E7 00091 * @param longitude global position * 1E7 00092 * @param altitude global position * 1000 00093 */ 00094 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00095 00096 static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) 00097 { 00098 mavlink_message_t msg; 00099 mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, latitude, longitude, altitude); 00100 mavlink_send_uart(chan, &msg); 00101 } 00102 00103 #endif 00104 // MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING 00105 00106 /** 00107 * @brief Get field target_system from gps_set_global_origin message 00108 * 00109 * @return System ID 00110 */ 00111 static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg) 00112 { 00113 return (uint8_t)(msg->payload)[0]; 00114 } 00115 00116 /** 00117 * @brief Get field target_component from gps_set_global_origin message 00118 * 00119 * @return Component ID 00120 */ 00121 static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg) 00122 { 00123 return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; 00124 } 00125 00126 /** 00127 * @brief Get field latitude from gps_set_global_origin message 00128 * 00129 * @return global position * 1E7 00130 */ 00131 static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg) 00132 { 00133 generic_32bit r; 00134 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00135 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; 00136 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; 00137 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; 00138 return (int32_t)r.i; 00139 } 00140 00141 /** 00142 * @brief Get field longitude from gps_set_global_origin message 00143 * 00144 * @return global position * 1E7 00145 */ 00146 static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg) 00147 { 00148 generic_32bit r; 00149 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0]; 00150 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1]; 00151 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[2]; 00152 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[3]; 00153 return (int32_t)r.i; 00154 } 00155 00156 /** 00157 * @brief Get field altitude from gps_set_global_origin message 00158 * 00159 * @return global position * 1000 00160 */ 00161 static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg) 00162 { 00163 generic_32bit r; 00164 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0]; 00165 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1]; 00166 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2]; 00167 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3]; 00168 return (int32_t)r.i; 00169 } 00170 00171 /** 00172 * @brief Decode a gps_set_global_origin message into a struct 00173 * 00174 * @param msg The message to decode 00175 * @param gps_set_global_origin C-struct to decode the message contents into 00176 */ 00177 static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin) 00178 { 00179 gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg); 00180 gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg); 00181 gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg); 00182 gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg); 00183 gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg); 00184 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2