Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Committer:
shimniok
Date:
Fri Nov 30 16:11:53 2018 +0000
Revision:
25:bb5356402687
Parent:
0:a6a169de725f
Initial publish of revised version.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:a6a169de725f 1 // MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
shimniok 0:a6a169de725f 2
shimniok 0:a6a169de725f 3 #define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
shimniok 0:a6a169de725f 4
shimniok 0:a6a169de725f 5 typedef struct __mavlink_gps_set_global_origin_t
shimniok 0:a6a169de725f 6 {
shimniok 0:a6a169de725f 7 uint8_t target_system; ///< System ID
shimniok 0:a6a169de725f 8 uint8_t target_component; ///< Component ID
shimniok 0:a6a169de725f 9 int32_t latitude; ///< global position * 1E7
shimniok 0:a6a169de725f 10 int32_t longitude; ///< global position * 1E7
shimniok 0:a6a169de725f 11 int32_t altitude; ///< global position * 1000
shimniok 0:a6a169de725f 12
shimniok 0:a6a169de725f 13 } mavlink_gps_set_global_origin_t;
shimniok 0:a6a169de725f 14
shimniok 0:a6a169de725f 15
shimniok 0:a6a169de725f 16
shimniok 0:a6a169de725f 17 /**
shimniok 0:a6a169de725f 18 * @brief Pack a gps_set_global_origin message
shimniok 0:a6a169de725f 19 * @param system_id ID of this system
shimniok 0:a6a169de725f 20 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 21 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 22 *
shimniok 0:a6a169de725f 23 * @param target_system System ID
shimniok 0:a6a169de725f 24 * @param target_component Component ID
shimniok 0:a6a169de725f 25 * @param latitude global position * 1E7
shimniok 0:a6a169de725f 26 * @param longitude global position * 1E7
shimniok 0:a6a169de725f 27 * @param altitude global position * 1000
shimniok 0:a6a169de725f 28 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 29 */
shimniok 0:a6a169de725f 30 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)
shimniok 0:a6a169de725f 31 {
shimniok 0:a6a169de725f 32 uint16_t i = 0;
shimniok 0:a6a169de725f 33 msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
shimniok 0:a6a169de725f 34
shimniok 0:a6a169de725f 35 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 36 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 37 i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
shimniok 0:a6a169de725f 38 i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
shimniok 0:a6a169de725f 39 i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
shimniok 0:a6a169de725f 40
shimniok 0:a6a169de725f 41 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:a6a169de725f 42 }
shimniok 0:a6a169de725f 43
shimniok 0:a6a169de725f 44 /**
shimniok 0:a6a169de725f 45 * @brief Pack a gps_set_global_origin message
shimniok 0:a6a169de725f 46 * @param system_id ID of this system
shimniok 0:a6a169de725f 47 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 48 * @param chan The MAVLink channel this message was sent over
shimniok 0:a6a169de725f 49 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 50 * @param target_system System ID
shimniok 0:a6a169de725f 51 * @param target_component Component ID
shimniok 0:a6a169de725f 52 * @param latitude global position * 1E7
shimniok 0:a6a169de725f 53 * @param longitude global position * 1E7
shimniok 0:a6a169de725f 54 * @param altitude global position * 1000
shimniok 0:a6a169de725f 55 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 56 */
shimniok 0:a6a169de725f 57 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)
shimniok 0:a6a169de725f 58 {
shimniok 0:a6a169de725f 59 uint16_t i = 0;
shimniok 0:a6a169de725f 60 msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
shimniok 0:a6a169de725f 61
shimniok 0:a6a169de725f 62 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 63 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 64 i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7
shimniok 0:a6a169de725f 65 i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7
shimniok 0:a6a169de725f 66 i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000
shimniok 0:a6a169de725f 67
shimniok 0:a6a169de725f 68 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:a6a169de725f 69 }
shimniok 0:a6a169de725f 70
shimniok 0:a6a169de725f 71 /**
shimniok 0:a6a169de725f 72 * @brief Encode a gps_set_global_origin struct into a message
shimniok 0:a6a169de725f 73 *
shimniok 0:a6a169de725f 74 * @param system_id ID of this system
shimniok 0:a6a169de725f 75 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 76 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 77 * @param gps_set_global_origin C-struct to read the message contents from
shimniok 0:a6a169de725f 78 */
shimniok 0:a6a169de725f 79 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)
shimniok 0:a6a169de725f 80 {
shimniok 0:a6a169de725f 81 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);
shimniok 0:a6a169de725f 82 }
shimniok 0:a6a169de725f 83
shimniok 0:a6a169de725f 84 /**
shimniok 0:a6a169de725f 85 * @brief Send a gps_set_global_origin message
shimniok 0:a6a169de725f 86 * @param chan MAVLink channel to send the message
shimniok 0:a6a169de725f 87 *
shimniok 0:a6a169de725f 88 * @param target_system System ID
shimniok 0:a6a169de725f 89 * @param target_component Component ID
shimniok 0:a6a169de725f 90 * @param latitude global position * 1E7
shimniok 0:a6a169de725f 91 * @param longitude global position * 1E7
shimniok 0:a6a169de725f 92 * @param altitude global position * 1000
shimniok 0:a6a169de725f 93 */
shimniok 0:a6a169de725f 94 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:a6a169de725f 95
shimniok 0:a6a169de725f 96 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)
shimniok 0:a6a169de725f 97 {
shimniok 0:a6a169de725f 98 mavlink_message_t msg;
shimniok 0:a6a169de725f 99 mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, latitude, longitude, altitude);
shimniok 0:a6a169de725f 100 mavlink_send_uart(chan, &msg);
shimniok 0:a6a169de725f 101 }
shimniok 0:a6a169de725f 102
shimniok 0:a6a169de725f 103 #endif
shimniok 0:a6a169de725f 104 // MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
shimniok 0:a6a169de725f 105
shimniok 0:a6a169de725f 106 /**
shimniok 0:a6a169de725f 107 * @brief Get field target_system from gps_set_global_origin message
shimniok 0:a6a169de725f 108 *
shimniok 0:a6a169de725f 109 * @return System ID
shimniok 0:a6a169de725f 110 */
shimniok 0:a6a169de725f 111 static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 112 {
shimniok 0:a6a169de725f 113 return (uint8_t)(msg->payload)[0];
shimniok 0:a6a169de725f 114 }
shimniok 0:a6a169de725f 115
shimniok 0:a6a169de725f 116 /**
shimniok 0:a6a169de725f 117 * @brief Get field target_component from gps_set_global_origin message
shimniok 0:a6a169de725f 118 *
shimniok 0:a6a169de725f 119 * @return Component ID
shimniok 0:a6a169de725f 120 */
shimniok 0:a6a169de725f 121 static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 122 {
shimniok 0:a6a169de725f 123 return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
shimniok 0:a6a169de725f 124 }
shimniok 0:a6a169de725f 125
shimniok 0:a6a169de725f 126 /**
shimniok 0:a6a169de725f 127 * @brief Get field latitude from gps_set_global_origin message
shimniok 0:a6a169de725f 128 *
shimniok 0:a6a169de725f 129 * @return global position * 1E7
shimniok 0:a6a169de725f 130 */
shimniok 0:a6a169de725f 131 static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 132 {
shimniok 0:a6a169de725f 133 generic_32bit r;
shimniok 0:a6a169de725f 134 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:a6a169de725f 135 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
shimniok 0:a6a169de725f 136 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2];
shimniok 0:a6a169de725f 137 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3];
shimniok 0:a6a169de725f 138 return (int32_t)r.i;
shimniok 0:a6a169de725f 139 }
shimniok 0:a6a169de725f 140
shimniok 0:a6a169de725f 141 /**
shimniok 0:a6a169de725f 142 * @brief Get field longitude from gps_set_global_origin message
shimniok 0:a6a169de725f 143 *
shimniok 0:a6a169de725f 144 * @return global position * 1E7
shimniok 0:a6a169de725f 145 */
shimniok 0:a6a169de725f 146 static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 147 {
shimniok 0:a6a169de725f 148 generic_32bit r;
shimniok 0:a6a169de725f 149 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0];
shimniok 0:a6a169de725f 150 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1];
shimniok 0:a6a169de725f 151 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[2];
shimniok 0:a6a169de725f 152 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[3];
shimniok 0:a6a169de725f 153 return (int32_t)r.i;
shimniok 0:a6a169de725f 154 }
shimniok 0:a6a169de725f 155
shimniok 0:a6a169de725f 156 /**
shimniok 0:a6a169de725f 157 * @brief Get field altitude from gps_set_global_origin message
shimniok 0:a6a169de725f 158 *
shimniok 0:a6a169de725f 159 * @return global position * 1000
shimniok 0:a6a169de725f 160 */
shimniok 0:a6a169de725f 161 static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 162 {
shimniok 0:a6a169de725f 163 generic_32bit r;
shimniok 0:a6a169de725f 164 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0];
shimniok 0:a6a169de725f 165 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1];
shimniok 0:a6a169de725f 166 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2];
shimniok 0:a6a169de725f 167 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3];
shimniok 0:a6a169de725f 168 return (int32_t)r.i;
shimniok 0:a6a169de725f 169 }
shimniok 0:a6a169de725f 170
shimniok 0:a6a169de725f 171 /**
shimniok 0:a6a169de725f 172 * @brief Decode a gps_set_global_origin message into a struct
shimniok 0:a6a169de725f 173 *
shimniok 0:a6a169de725f 174 * @param msg The message to decode
shimniok 0:a6a169de725f 175 * @param gps_set_global_origin C-struct to decode the message contents into
shimniok 0:a6a169de725f 176 */
shimniok 0:a6a169de725f 177 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)
shimniok 0:a6a169de725f 178 {
shimniok 0:a6a169de725f 179 gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
shimniok 0:a6a169de725f 180 gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
shimniok 0:a6a169de725f 181 gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg);
shimniok 0:a6a169de725f 182 gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg);
shimniok 0:a6a169de725f 183 gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg);
shimniok 0:a6a169de725f 184 }