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