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 PARAM_SET PACKING
shimniok 0:a6a169de725f 2
shimniok 0:a6a169de725f 3 #define MAVLINK_MSG_ID_PARAM_SET 23
shimniok 0:a6a169de725f 4
shimniok 0:a6a169de725f 5 typedef struct __mavlink_param_set_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 int8_t param_id[15]; ///< Onboard parameter id
shimniok 0:a6a169de725f 10 float param_value; ///< Onboard parameter value
shimniok 0:a6a169de725f 11
shimniok 0:a6a169de725f 12 } mavlink_param_set_t;
shimniok 0:a6a169de725f 13
shimniok 0:a6a169de725f 14 #define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15
shimniok 0:a6a169de725f 15
shimniok 0:a6a169de725f 16
shimniok 0:a6a169de725f 17 /**
shimniok 0:a6a169de725f 18 * @brief Pack a param_set 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 param_id Onboard parameter id
shimniok 0:a6a169de725f 26 * @param param_value Onboard parameter value
shimniok 0:a6a169de725f 27 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 28 */
shimniok 0:a6a169de725f 29 static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
shimniok 0:a6a169de725f 30 {
shimniok 0:a6a169de725f 31 uint16_t i = 0;
shimniok 0:a6a169de725f 32 msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
shimniok 0:a6a169de725f 33
shimniok 0:a6a169de725f 34 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 35 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 36 i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
shimniok 0:a6a169de725f 37 i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
shimniok 0:a6a169de725f 38
shimniok 0:a6a169de725f 39 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:a6a169de725f 40 }
shimniok 0:a6a169de725f 41
shimniok 0:a6a169de725f 42 /**
shimniok 0:a6a169de725f 43 * @brief Pack a param_set message
shimniok 0:a6a169de725f 44 * @param system_id ID of this system
shimniok 0:a6a169de725f 45 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 46 * @param chan The MAVLink channel this message was sent over
shimniok 0:a6a169de725f 47 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 48 * @param target_system System ID
shimniok 0:a6a169de725f 49 * @param target_component Component ID
shimniok 0:a6a169de725f 50 * @param param_id Onboard parameter id
shimniok 0:a6a169de725f 51 * @param param_value Onboard parameter value
shimniok 0:a6a169de725f 52 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 53 */
shimniok 0:a6a169de725f 54 static inline uint16_t mavlink_msg_param_set_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, const int8_t* param_id, float param_value)
shimniok 0:a6a169de725f 55 {
shimniok 0:a6a169de725f 56 uint16_t i = 0;
shimniok 0:a6a169de725f 57 msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
shimniok 0:a6a169de725f 58
shimniok 0:a6a169de725f 59 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 60 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 61 i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
shimniok 0:a6a169de725f 62 i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
shimniok 0:a6a169de725f 63
shimniok 0:a6a169de725f 64 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:a6a169de725f 65 }
shimniok 0:a6a169de725f 66
shimniok 0:a6a169de725f 67 /**
shimniok 0:a6a169de725f 68 * @brief Encode a param_set struct into a message
shimniok 0:a6a169de725f 69 *
shimniok 0:a6a169de725f 70 * @param system_id ID of this system
shimniok 0:a6a169de725f 71 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 72 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 73 * @param param_set C-struct to read the message contents from
shimniok 0:a6a169de725f 74 */
shimniok 0:a6a169de725f 75 static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
shimniok 0:a6a169de725f 76 {
shimniok 0:a6a169de725f 77 return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value);
shimniok 0:a6a169de725f 78 }
shimniok 0:a6a169de725f 79
shimniok 0:a6a169de725f 80 /**
shimniok 0:a6a169de725f 81 * @brief Send a param_set message
shimniok 0:a6a169de725f 82 * @param chan MAVLink channel to send the message
shimniok 0:a6a169de725f 83 *
shimniok 0:a6a169de725f 84 * @param target_system System ID
shimniok 0:a6a169de725f 85 * @param target_component Component ID
shimniok 0:a6a169de725f 86 * @param param_id Onboard parameter id
shimniok 0:a6a169de725f 87 * @param param_value Onboard parameter value
shimniok 0:a6a169de725f 88 */
shimniok 0:a6a169de725f 89 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:a6a169de725f 90
shimniok 0:a6a169de725f 91 static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t* param_id, float param_value)
shimniok 0:a6a169de725f 92 {
shimniok 0:a6a169de725f 93 mavlink_message_t msg;
shimniok 0:a6a169de725f 94 mavlink_msg_param_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, param_id, param_value);
shimniok 0:a6a169de725f 95 mavlink_send_uart(chan, &msg);
shimniok 0:a6a169de725f 96 }
shimniok 0:a6a169de725f 97
shimniok 0:a6a169de725f 98 #endif
shimniok 0:a6a169de725f 99 // MESSAGE PARAM_SET UNPACKING
shimniok 0:a6a169de725f 100
shimniok 0:a6a169de725f 101 /**
shimniok 0:a6a169de725f 102 * @brief Get field target_system from param_set message
shimniok 0:a6a169de725f 103 *
shimniok 0:a6a169de725f 104 * @return System ID
shimniok 0:a6a169de725f 105 */
shimniok 0:a6a169de725f 106 static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 107 {
shimniok 0:a6a169de725f 108 return (uint8_t)(msg->payload)[0];
shimniok 0:a6a169de725f 109 }
shimniok 0:a6a169de725f 110
shimniok 0:a6a169de725f 111 /**
shimniok 0:a6a169de725f 112 * @brief Get field target_component from param_set message
shimniok 0:a6a169de725f 113 *
shimniok 0:a6a169de725f 114 * @return Component ID
shimniok 0:a6a169de725f 115 */
shimniok 0:a6a169de725f 116 static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 117 {
shimniok 0:a6a169de725f 118 return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
shimniok 0:a6a169de725f 119 }
shimniok 0:a6a169de725f 120
shimniok 0:a6a169de725f 121 /**
shimniok 0:a6a169de725f 122 * @brief Get field param_id from param_set message
shimniok 0:a6a169de725f 123 *
shimniok 0:a6a169de725f 124 * @return Onboard parameter id
shimniok 0:a6a169de725f 125 */
shimniok 0:a6a169de725f 126 static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, int8_t* r_data)
shimniok 0:a6a169de725f 127 {
shimniok 0:a6a169de725f 128
shimniok 0:a6a169de725f 129 memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t), 15);
shimniok 0:a6a169de725f 130 return 15;
shimniok 0:a6a169de725f 131 }
shimniok 0:a6a169de725f 132
shimniok 0:a6a169de725f 133 /**
shimniok 0:a6a169de725f 134 * @brief Get field param_value from param_set message
shimniok 0:a6a169de725f 135 *
shimniok 0:a6a169de725f 136 * @return Onboard parameter value
shimniok 0:a6a169de725f 137 */
shimniok 0:a6a169de725f 138 static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 139 {
shimniok 0:a6a169de725f 140 generic_32bit r;
shimniok 0:a6a169de725f 141 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[0];
shimniok 0:a6a169de725f 142 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[1];
shimniok 0:a6a169de725f 143 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[2];
shimniok 0:a6a169de725f 144 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+15)[3];
shimniok 0:a6a169de725f 145 return (float)r.f;
shimniok 0:a6a169de725f 146 }
shimniok 0:a6a169de725f 147
shimniok 0:a6a169de725f 148 /**
shimniok 0:a6a169de725f 149 * @brief Decode a param_set message into a struct
shimniok 0:a6a169de725f 150 *
shimniok 0:a6a169de725f 151 * @param msg The message to decode
shimniok 0:a6a169de725f 152 * @param param_set C-struct to decode the message contents into
shimniok 0:a6a169de725f 153 */
shimniok 0:a6a169de725f 154 static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
shimniok 0:a6a169de725f 155 {
shimniok 0:a6a169de725f 156 param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
shimniok 0:a6a169de725f 157 param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
shimniok 0:a6a169de725f 158 mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
shimniok 0:a6a169de725f 159 param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
shimniok 0:a6a169de725f 160 }