Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE WAYPOINT_CURRENT PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_waypoint_current_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint16_t seq; ///< Sequence
shimniok 0:826c6171fc1b 8
shimniok 0:826c6171fc1b 9 } mavlink_waypoint_current_t;
shimniok 0:826c6171fc1b 10
shimniok 0:826c6171fc1b 11
shimniok 0:826c6171fc1b 12
shimniok 0:826c6171fc1b 13 /**
shimniok 0:826c6171fc1b 14 * @brief Pack a waypoint_current message
shimniok 0:826c6171fc1b 15 * @param system_id ID of this system
shimniok 0:826c6171fc1b 16 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 17 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 18 *
shimniok 0:826c6171fc1b 19 * @param seq Sequence
shimniok 0:826c6171fc1b 20 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 21 */
shimniok 0:826c6171fc1b 22 static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seq)
shimniok 0:826c6171fc1b 23 {
shimniok 0:826c6171fc1b 24 uint16_t i = 0;
shimniok 0:826c6171fc1b 25 msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
shimniok 0:826c6171fc1b 26
shimniok 0:826c6171fc1b 27 i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
shimniok 0:826c6171fc1b 28
shimniok 0:826c6171fc1b 29 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 30 }
shimniok 0:826c6171fc1b 31
shimniok 0:826c6171fc1b 32 /**
shimniok 0:826c6171fc1b 33 * @brief Pack a waypoint_current message
shimniok 0:826c6171fc1b 34 * @param system_id ID of this system
shimniok 0:826c6171fc1b 35 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 36 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 37 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 38 * @param seq Sequence
shimniok 0:826c6171fc1b 39 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 40 */
shimniok 0:826c6171fc1b 41 static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
shimniok 0:826c6171fc1b 42 {
shimniok 0:826c6171fc1b 43 uint16_t i = 0;
shimniok 0:826c6171fc1b 44 msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
shimniok 0:826c6171fc1b 45
shimniok 0:826c6171fc1b 46 i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
shimniok 0:826c6171fc1b 47
shimniok 0:826c6171fc1b 48 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 49 }
shimniok 0:826c6171fc1b 50
shimniok 0:826c6171fc1b 51 /**
shimniok 0:826c6171fc1b 52 * @brief Encode a waypoint_current struct into a message
shimniok 0:826c6171fc1b 53 *
shimniok 0:826c6171fc1b 54 * @param system_id ID of this system
shimniok 0:826c6171fc1b 55 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 56 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 57 * @param waypoint_current C-struct to read the message contents from
shimniok 0:826c6171fc1b 58 */
shimniok 0:826c6171fc1b 59 static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
shimniok 0:826c6171fc1b 60 {
shimniok 0:826c6171fc1b 61 return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
shimniok 0:826c6171fc1b 62 }
shimniok 0:826c6171fc1b 63
shimniok 0:826c6171fc1b 64 /**
shimniok 0:826c6171fc1b 65 * @brief Send a waypoint_current message
shimniok 0:826c6171fc1b 66 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 67 *
shimniok 0:826c6171fc1b 68 * @param seq Sequence
shimniok 0:826c6171fc1b 69 */
shimniok 0:826c6171fc1b 70 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 71
shimniok 0:826c6171fc1b 72 static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
shimniok 0:826c6171fc1b 73 {
shimniok 0:826c6171fc1b 74 mavlink_message_t msg;
shimniok 0:826c6171fc1b 75 mavlink_msg_waypoint_current_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq);
shimniok 0:826c6171fc1b 76 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 77 }
shimniok 0:826c6171fc1b 78
shimniok 0:826c6171fc1b 79 #endif
shimniok 0:826c6171fc1b 80 // MESSAGE WAYPOINT_CURRENT UNPACKING
shimniok 0:826c6171fc1b 81
shimniok 0:826c6171fc1b 82 /**
shimniok 0:826c6171fc1b 83 * @brief Get field seq from waypoint_current message
shimniok 0:826c6171fc1b 84 *
shimniok 0:826c6171fc1b 85 * @return Sequence
shimniok 0:826c6171fc1b 86 */
shimniok 0:826c6171fc1b 87 static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 88 {
shimniok 0:826c6171fc1b 89 generic_16bit r;
shimniok 0:826c6171fc1b 90 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 91 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 92 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 93 }
shimniok 0:826c6171fc1b 94
shimniok 0:826c6171fc1b 95 /**
shimniok 0:826c6171fc1b 96 * @brief Decode a waypoint_current message into a struct
shimniok 0:826c6171fc1b 97 *
shimniok 0:826c6171fc1b 98 * @param msg The message to decode
shimniok 0:826c6171fc1b 99 * @param waypoint_current C-struct to decode the message contents into
shimniok 0:826c6171fc1b 100 */
shimniok 0:826c6171fc1b 101 static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current)
shimniok 0:826c6171fc1b 102 {
shimniok 0:826c6171fc1b 103 waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg);
shimniok 0:826c6171fc1b 104 }