mavlink_msg_gps_date_time.h 4.96 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143
// MESSAGE GPS_DATE_TIME PACKING

#define MAVLINK_MSG_ID_GPS_DATE_TIME 179

typedef struct __mavlink_gps_date_time_t 
{
	uint8_t year; ///< Year reported by Gps 
	uint8_t month; ///< Month reported by Gps 
	uint8_t day; ///< Day reported by Gps 
	uint8_t hour; ///< Hour reported by Gps 
	uint8_t min; ///< Min reported by Gps 
	uint8_t sec; ///< Sec reported by Gps  
	uint8_t visSat; ///< Visible sattelites reported by Gps  

} mavlink_gps_date_time_t;



/**
 * @brief Send a gps_date_time message
 *
 * @param year Year reported by Gps 
 * @param month Month reported by Gps 
 * @param day Day reported by Gps 
 * @param hour Hour reported by Gps 
 * @param min Min reported by Gps 
 * @param sec Sec reported by Gps  
 * @param visSat Visible sattelites reported by Gps  
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
	uint16_t i = 0;
	msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;

	i += put_uint8_t_by_index(year, i, msg->payload); //Year reported by Gps 
	i += put_uint8_t_by_index(month, i, msg->payload); //Month reported by Gps 
	i += put_uint8_t_by_index(day, i, msg->payload); //Day reported by Gps 
	i += put_uint8_t_by_index(hour, i, msg->payload); //Hour reported by Gps 
	i += put_uint8_t_by_index(min, i, msg->payload); //Min reported by Gps 
	i += put_uint8_t_by_index(sec, i, msg->payload); //Sec reported by Gps  
	i += put_uint8_t_by_index(visSat, i, msg->payload); //Visible sattelites reported by Gps  

	return mavlink_finalize_message(msg, system_id, component_id, i);
}

static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time)
{
	return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat);
}

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
{
	mavlink_message_t msg;
	mavlink_msg_gps_date_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, year, month, day, hour, min, sec, visSat);
	mavlink_send_uart(chan, &msg);
}

#endif
// MESSAGE GPS_DATE_TIME UNPACKING

/**
 * @brief Get field year from gps_date_time message
 *
 * @return Year reported by Gps 
 */
static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload)[0];
}

/**
 * @brief Get field month from gps_date_time message
 *
 * @return Month reported by Gps 
 */
static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}

/**
 * @brief Get field day from gps_date_time message
 *
 * @return Day reported by Gps 
 */
static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}

/**
 * @brief Get field hour from gps_date_time message
 *
 * @return Hour reported by Gps 
 */
static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}

/**
 * @brief Get field min from gps_date_time message
 *
 * @return Min reported by Gps 
 */
static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}

/**
 * @brief Get field sec from gps_date_time message
 *
 * @return Sec reported by Gps  
 */
static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}

/**
 * @brief Get field visSat from gps_date_time message
 *
 * @return Visible sattelites reported by Gps  
 */
static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg)
{
	return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}

static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time)
{
	gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg);
	gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg);
	gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg);
	gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg);
	gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg);
	gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg);
	gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg);
}