Added --force to svn add on sync script to find new unversioned files.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1098 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
james.goppert 2010-12-09 06:05:48 +00:00
parent e2e3b9eee9
commit c7a8291725
4 changed files with 607 additions and 1 deletions

View File

@ -0,0 +1,156 @@
// MESSAGE DEBUG_VECT PACKING
#define MAVLINK_MSG_ID_DEBUG_VECT 70
typedef struct __mavlink_debug_vect_t
{
int8_t name[10]; ///< Name
uint64_t usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
} mavlink_debug_vect_t;
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
/**
* @brief Send a debug_vect message
*
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const int8_t* name, uint64_t usec, float x, float y, float z)
{
mavlink_message_t msg;
mavlink_msg_debug_vect_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, usec, x, y, z);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE DEBUG_VECT UNPACKING
/**
* @brief Get field name from debug_vect message
*
* @return Name
*/
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, int8_t* r_data)
{
memcpy(r_data, msg->payload, 10);
return 10;
}
/**
* @brief Get field usec from debug_vect message
*
* @return Timestamp
*/
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
{
generic_64bit r;
r.b[7] = (msg->payload+10)[0];
r.b[6] = (msg->payload+10)[1];
r.b[5] = (msg->payload+10)[2];
r.b[4] = (msg->payload+10)[3];
r.b[3] = (msg->payload+10)[4];
r.b[2] = (msg->payload+10)[5];
r.b[1] = (msg->payload+10)[6];
r.b[0] = (msg->payload+10)[7];
return (uint64_t)r.ll;
}
/**
* @brief Get field x from debug_vect message
*
* @return x
*/
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t))[3];
return (float)r.f;
}
/**
* @brief Get field y from debug_vect message
*
* @return y
*/
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from debug_vect message
*
* @return z
*/
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
}

View File

@ -0,0 +1,195 @@
// MESSAGE POINT_OF_INTEREST PACKING
#define MAVLINK_MSG_ID_POINT_OF_INTEREST 161
typedef struct __mavlink_point_of_interest_t
{
uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
uint8_t coordinate_system; ///< 0: global, 1:local
uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
int8_t name[25]; ///< POI name
} mavlink_point_of_interest_t;
#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 25
/**
* @brief Send a point_of_interest message
*
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param name POI name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_array_by_index(name, 25, i, msg->payload); //POI name
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_array_by_index(name, 25, i, msg->payload); //POI name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
{
return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const int8_t* name)
{
mavlink_message_t msg;
mavlink_msg_point_of_interest_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, x, y, z, name);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE POINT_OF_INTEREST UNPACKING
/**
* @brief Get field type from point_of_interest message
*
* @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
*/
static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field color from point_of_interest message
*
* @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
*/
static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field coordinate_system from point_of_interest message
*
* @return 0: global, 1:local
*/
static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field timeout from point_of_interest message
*
* @return 0: no timeout, >1: timeout in seconds
*/
static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field x from point_of_interest message
*
* @return X Position
*/
static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
return (float)r.f;
}
/**
* @brief Get field y from point_of_interest message
*
* @return Y Position
*/
static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from point_of_interest message
*
* @return Z Position
*/
static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field name from point_of_interest message
*
* @return POI name
*/
static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, int8_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float), 25);
return 25;
}
static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest)
{
point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg);
point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg);
point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg);
point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg);
point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg);
point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg);
point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg);
mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name);
}

View File

@ -0,0 +1,255 @@
// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING
#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 162
typedef struct __mavlink_point_of_interest_connection_t
{
uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
uint8_t coordinate_system; ///< 0: global, 1:local
uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
float xp1; ///< X1 Position
float yp1; ///< Y1 Position
float zp1; ///< Z1 Position
float xp2; ///< X2 Position
float yp2; ///< Y2 Position
float zp2; ///< Z2 Position
int8_t name[25]; ///< POI connection name
} mavlink_point_of_interest_connection_t;
#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 25
/**
* @brief Send a point_of_interest_connection message
*
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param xp1 X1 Position
* @param yp1 Y1 Position
* @param zp1 Z1 Position
* @param xp2 X2 Position
* @param yp2 Y2 Position
* @param zp2 Z2 Position
* @param name POI connection name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); //X1 Position
i += put_float_by_index(yp1, i, msg->payload); //Y1 Position
i += put_float_by_index(zp1, i, msg->payload); //Z1 Position
i += put_float_by_index(xp2, i, msg->payload); //X2 Position
i += put_float_by_index(yp2, i, msg->payload); //Y2 Position
i += put_float_by_index(zp2, i, msg->payload); //Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); //POI connection name
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); //X1 Position
i += put_float_by_index(yp1, i, msg->payload); //Y1 Position
i += put_float_by_index(zp1, i, msg->payload); //Z1 Position
i += put_float_by_index(xp2, i, msg->payload); //X2 Position
i += put_float_by_index(yp2, i, msg->payload); //Y2 Position
i += put_float_by_index(zp2, i, msg->payload); //Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); //POI connection name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
{
return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const int8_t* name)
{
mavlink_message_t msg;
mavlink_msg_point_of_interest_connection_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, color, coordinate_system, timeout, xp1, yp1, zp1, xp2, yp2, zp2, name);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING
/**
* @brief Get field type from point_of_interest_connection message
*
* @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
*/
static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field color from point_of_interest_connection message
*
* @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
*/
static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field coordinate_system from point_of_interest_connection message
*
* @return 0: global, 1:local
*/
static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field timeout from point_of_interest_connection message
*
* @return 0: no timeout, >1: timeout in seconds
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
return (uint16_t)r.s;
}
/**
* @brief Get field xp1 from point_of_interest_connection message
*
* @return X1 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
return (float)r.f;
}
/**
* @brief Get field yp1 from point_of_interest_connection message
*
* @return Y1 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field zp1 from point_of_interest_connection message
*
* @return Z1 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field xp2 from point_of_interest_connection message
*
* @return X2 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field yp2 from point_of_interest_connection message
*
* @return Y2 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field zp2 from point_of_interest_connection message
*
* @return Z2 Position
*/
static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field name from point_of_interest_connection message
*
* @return POI connection name
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, int8_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float), 25);
return 25;
}
static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection)
{
point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg);
point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg);
point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg);
point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg);
point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg);
point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg);
point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg);
point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg);
point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg);
point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg);
mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name);
}

View File

@ -4,4 +4,4 @@ git clone git://github.com/pixhawk/mavlink.git -b dev _tmp
rm -rf _tmp/.git rm -rf _tmp/.git
rsync -av _tmp/* . rsync -av _tmp/* .
rm -rf _tmp rm -rf _tmp
svn add * svn add --force *