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
MAVlink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h@25:bb5356402687, 2018-11-30 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
shimniok | 0:a6a169de725f | 1 | // MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING |
shimniok | 0:a6a169de725f | 2 | |
shimniok | 0:a6a169de725f | 3 | #define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 55 |
shimniok | 0:a6a169de725f | 4 | |
shimniok | 0:a6a169de725f | 5 | typedef struct __mavlink_set_roll_pitch_yaw_thrust_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 | float roll; ///< Desired roll angle in radians |
shimniok | 0:a6a169de725f | 10 | float pitch; ///< Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 11 | float yaw; ///< Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 12 | float thrust; ///< Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 13 | |
shimniok | 0:a6a169de725f | 14 | } mavlink_set_roll_pitch_yaw_thrust_t; |
shimniok | 0:a6a169de725f | 15 | |
shimniok | 0:a6a169de725f | 16 | |
shimniok | 0:a6a169de725f | 17 | |
shimniok | 0:a6a169de725f | 18 | /** |
shimniok | 0:a6a169de725f | 19 | * @brief Pack a set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 20 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 21 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 22 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 23 | * |
shimniok | 0:a6a169de725f | 24 | * @param target_system System ID |
shimniok | 0:a6a169de725f | 25 | * @param target_component Component ID |
shimniok | 0:a6a169de725f | 26 | * @param roll Desired roll angle in radians |
shimniok | 0:a6a169de725f | 27 | * @param pitch Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 28 | * @param yaw Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 29 | * @param thrust Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 30 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:a6a169de725f | 31 | */ |
shimniok | 0:a6a169de725f | 32 | static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) |
shimniok | 0:a6a169de725f | 33 | { |
shimniok | 0:a6a169de725f | 34 | uint16_t i = 0; |
shimniok | 0:a6a169de725f | 35 | msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; |
shimniok | 0:a6a169de725f | 36 | |
shimniok | 0:a6a169de725f | 37 | i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID |
shimniok | 0:a6a169de725f | 38 | i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID |
shimniok | 0:a6a169de725f | 39 | i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians |
shimniok | 0:a6a169de725f | 40 | i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 41 | i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 42 | i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 43 | |
shimniok | 0:a6a169de725f | 44 | return mavlink_finalize_message(msg, system_id, component_id, i); |
shimniok | 0:a6a169de725f | 45 | } |
shimniok | 0:a6a169de725f | 46 | |
shimniok | 0:a6a169de725f | 47 | /** |
shimniok | 0:a6a169de725f | 48 | * @brief Pack a set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 49 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 50 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 51 | * @param chan The MAVLink channel this message was sent over |
shimniok | 0:a6a169de725f | 52 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 53 | * @param target_system System ID |
shimniok | 0:a6a169de725f | 54 | * @param target_component Component ID |
shimniok | 0:a6a169de725f | 55 | * @param roll Desired roll angle in radians |
shimniok | 0:a6a169de725f | 56 | * @param pitch Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 57 | * @param yaw Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 58 | * @param thrust Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 59 | * @return length of the message in bytes (excluding serial stream start sign) |
shimniok | 0:a6a169de725f | 60 | */ |
shimniok | 0:a6a169de725f | 61 | static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_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, float roll, float pitch, float yaw, float thrust) |
shimniok | 0:a6a169de725f | 62 | { |
shimniok | 0:a6a169de725f | 63 | uint16_t i = 0; |
shimniok | 0:a6a169de725f | 64 | msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; |
shimniok | 0:a6a169de725f | 65 | |
shimniok | 0:a6a169de725f | 66 | i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID |
shimniok | 0:a6a169de725f | 67 | i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID |
shimniok | 0:a6a169de725f | 68 | i += put_float_by_index(roll, i, msg->payload); // Desired roll angle in radians |
shimniok | 0:a6a169de725f | 69 | i += put_float_by_index(pitch, i, msg->payload); // Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 70 | i += put_float_by_index(yaw, i, msg->payload); // Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 71 | i += put_float_by_index(thrust, i, msg->payload); // Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 72 | |
shimniok | 0:a6a169de725f | 73 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); |
shimniok | 0:a6a169de725f | 74 | } |
shimniok | 0:a6a169de725f | 75 | |
shimniok | 0:a6a169de725f | 76 | /** |
shimniok | 0:a6a169de725f | 77 | * @brief Encode a set_roll_pitch_yaw_thrust struct into a message |
shimniok | 0:a6a169de725f | 78 | * |
shimniok | 0:a6a169de725f | 79 | * @param system_id ID of this system |
shimniok | 0:a6a169de725f | 80 | * @param component_id ID of this component (e.g. 200 for IMU) |
shimniok | 0:a6a169de725f | 81 | * @param msg The MAVLink message to compress the data into |
shimniok | 0:a6a169de725f | 82 | * @param set_roll_pitch_yaw_thrust C-struct to read the message contents from |
shimniok | 0:a6a169de725f | 83 | */ |
shimniok | 0:a6a169de725f | 84 | static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) |
shimniok | 0:a6a169de725f | 85 | { |
shimniok | 0:a6a169de725f | 86 | return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust); |
shimniok | 0:a6a169de725f | 87 | } |
shimniok | 0:a6a169de725f | 88 | |
shimniok | 0:a6a169de725f | 89 | /** |
shimniok | 0:a6a169de725f | 90 | * @brief Send a set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 91 | * @param chan MAVLink channel to send the message |
shimniok | 0:a6a169de725f | 92 | * |
shimniok | 0:a6a169de725f | 93 | * @param target_system System ID |
shimniok | 0:a6a169de725f | 94 | * @param target_component Component ID |
shimniok | 0:a6a169de725f | 95 | * @param roll Desired roll angle in radians |
shimniok | 0:a6a169de725f | 96 | * @param pitch Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 97 | * @param yaw Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 98 | * @param thrust Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 99 | */ |
shimniok | 0:a6a169de725f | 100 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
shimniok | 0:a6a169de725f | 101 | |
shimniok | 0:a6a169de725f | 102 | static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) |
shimniok | 0:a6a169de725f | 103 | { |
shimniok | 0:a6a169de725f | 104 | mavlink_message_t msg; |
shimniok | 0:a6a169de725f | 105 | mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, roll, pitch, yaw, thrust); |
shimniok | 0:a6a169de725f | 106 | mavlink_send_uart(chan, &msg); |
shimniok | 0:a6a169de725f | 107 | } |
shimniok | 0:a6a169de725f | 108 | |
shimniok | 0:a6a169de725f | 109 | #endif |
shimniok | 0:a6a169de725f | 110 | // MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING |
shimniok | 0:a6a169de725f | 111 | |
shimniok | 0:a6a169de725f | 112 | /** |
shimniok | 0:a6a169de725f | 113 | * @brief Get field target_system from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 114 | * |
shimniok | 0:a6a169de725f | 115 | * @return System ID |
shimniok | 0:a6a169de725f | 116 | */ |
shimniok | 0:a6a169de725f | 117 | static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 118 | { |
shimniok | 0:a6a169de725f | 119 | return (uint8_t)(msg->payload)[0]; |
shimniok | 0:a6a169de725f | 120 | } |
shimniok | 0:a6a169de725f | 121 | |
shimniok | 0:a6a169de725f | 122 | /** |
shimniok | 0:a6a169de725f | 123 | * @brief Get field target_component from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 124 | * |
shimniok | 0:a6a169de725f | 125 | * @return Component ID |
shimniok | 0:a6a169de725f | 126 | */ |
shimniok | 0:a6a169de725f | 127 | static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 128 | { |
shimniok | 0:a6a169de725f | 129 | return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; |
shimniok | 0:a6a169de725f | 130 | } |
shimniok | 0:a6a169de725f | 131 | |
shimniok | 0:a6a169de725f | 132 | /** |
shimniok | 0:a6a169de725f | 133 | * @brief Get field roll from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 134 | * |
shimniok | 0:a6a169de725f | 135 | * @return Desired roll angle in radians |
shimniok | 0:a6a169de725f | 136 | */ |
shimniok | 0:a6a169de725f | 137 | static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 138 | { |
shimniok | 0:a6a169de725f | 139 | generic_32bit r; |
shimniok | 0:a6a169de725f | 140 | r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; |
shimniok | 0:a6a169de725f | 141 | r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; |
shimniok | 0:a6a169de725f | 142 | r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; |
shimniok | 0:a6a169de725f | 143 | r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; |
shimniok | 0:a6a169de725f | 144 | return (float)r.f; |
shimniok | 0:a6a169de725f | 145 | } |
shimniok | 0:a6a169de725f | 146 | |
shimniok | 0:a6a169de725f | 147 | /** |
shimniok | 0:a6a169de725f | 148 | * @brief Get field pitch from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 149 | * |
shimniok | 0:a6a169de725f | 150 | * @return Desired pitch angle in radians |
shimniok | 0:a6a169de725f | 151 | */ |
shimniok | 0:a6a169de725f | 152 | static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 153 | { |
shimniok | 0:a6a169de725f | 154 | generic_32bit r; |
shimniok | 0:a6a169de725f | 155 | r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[0]; |
shimniok | 0:a6a169de725f | 156 | r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[1]; |
shimniok | 0:a6a169de725f | 157 | r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[2]; |
shimniok | 0:a6a169de725f | 158 | r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float))[3]; |
shimniok | 0:a6a169de725f | 159 | return (float)r.f; |
shimniok | 0:a6a169de725f | 160 | } |
shimniok | 0:a6a169de725f | 161 | |
shimniok | 0:a6a169de725f | 162 | /** |
shimniok | 0:a6a169de725f | 163 | * @brief Get field yaw from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 164 | * |
shimniok | 0:a6a169de725f | 165 | * @return Desired yaw angle in radians |
shimniok | 0:a6a169de725f | 166 | */ |
shimniok | 0:a6a169de725f | 167 | static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 168 | { |
shimniok | 0:a6a169de725f | 169 | generic_32bit r; |
shimniok | 0:a6a169de725f | 170 | r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:a6a169de725f | 171 | r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:a6a169de725f | 172 | r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:a6a169de725f | 173 | r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:a6a169de725f | 174 | return (float)r.f; |
shimniok | 0:a6a169de725f | 175 | } |
shimniok | 0:a6a169de725f | 176 | |
shimniok | 0:a6a169de725f | 177 | /** |
shimniok | 0:a6a169de725f | 178 | * @brief Get field thrust from set_roll_pitch_yaw_thrust message |
shimniok | 0:a6a169de725f | 179 | * |
shimniok | 0:a6a169de725f | 180 | * @return Collective thrust, normalized to 0 .. 1 |
shimniok | 0:a6a169de725f | 181 | */ |
shimniok | 0:a6a169de725f | 182 | static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg) |
shimniok | 0:a6a169de725f | 183 | { |
shimniok | 0:a6a169de725f | 184 | generic_32bit r; |
shimniok | 0:a6a169de725f | 185 | r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; |
shimniok | 0:a6a169de725f | 186 | r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; |
shimniok | 0:a6a169de725f | 187 | r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; |
shimniok | 0:a6a169de725f | 188 | r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; |
shimniok | 0:a6a169de725f | 189 | return (float)r.f; |
shimniok | 0:a6a169de725f | 190 | } |
shimniok | 0:a6a169de725f | 191 | |
shimniok | 0:a6a169de725f | 192 | /** |
shimniok | 0:a6a169de725f | 193 | * @brief Decode a set_roll_pitch_yaw_thrust message into a struct |
shimniok | 0:a6a169de725f | 194 | * |
shimniok | 0:a6a169de725f | 195 | * @param msg The message to decode |
shimniok | 0:a6a169de725f | 196 | * @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into |
shimniok | 0:a6a169de725f | 197 | */ |
shimniok | 0:a6a169de725f | 198 | static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) |
shimniok | 0:a6a169de725f | 199 | { |
shimniok | 0:a6a169de725f | 200 | set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg); |
shimniok | 0:a6a169de725f | 201 | set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg); |
shimniok | 0:a6a169de725f | 202 | set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg); |
shimniok | 0:a6a169de725f | 203 | set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg); |
shimniok | 0:a6a169de725f | 204 | set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg); |
shimniok | 0:a6a169de725f | 205 | set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg); |
shimniok | 0:a6a169de725f | 206 | } |