Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
241d6c36
Commit
241d6c36
authored
Aug 02, 2011
by
oberion
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
added SenseSoar Mavlink Messages
parent
0641c635
Changes
26
Hide whitespace changes
Inline
Side-by-side
Showing
26 changed files
with
2313 additions
and
3 deletions
+2313
-3
.gitignore
.gitignore
+1
-0
qgroundcontrol.pro
qgroundcontrol.pro
+10
-0
SenseSoar.h
thirdParty/mavlink/include/SenseSoar/SenseSoar.h
+73
-0
mavlink.h
thirdParty/mavlink/include/SenseSoar/mavlink.h
+11
-0
mavlink_msg_cmd_airspeed_ack.h
.../mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_ack.h
+123
-0
mavlink_msg_cmd_airspeed_chng.h
...mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_chng.h
+123
-0
mavlink_msg_filt_rot_vel.h
...arty/mavlink/include/SenseSoar/mavlink_msg_filt_rot_vel.h
+104
-0
mavlink_msg_llc_out.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_llc_out.h
+124
-0
mavlink_msg_obs_air_temp.h
...arty/mavlink/include/SenseSoar/mavlink_msg_obs_air_temp.h
+106
-0
mavlink_msg_obs_air_velocity.h
.../mavlink/include/SenseSoar/mavlink_msg_obs_air_velocity.h
+150
-0
mavlink_msg_obs_attitude.h
...arty/mavlink/include/SenseSoar/mavlink_msg_obs_attitude.h
+104
-0
mavlink_msg_obs_bias.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_obs_bias.h
+124
-0
mavlink_msg_obs_position.h
...arty/mavlink/include/SenseSoar/mavlink_msg_obs_position.h
+104
-0
mavlink_msg_obs_qff.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_obs_qff.h
+106
-0
mavlink_msg_obs_velocity.h
...arty/mavlink/include/SenseSoar/mavlink_msg_obs_velocity.h
+104
-0
mavlink_msg_obs_wind.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_obs_wind.h
+104
-0
mavlink_msg_pm_elec.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_pm_elec.h
+148
-0
mavlink_msg_sensesoar_mode_ack.h
...avlink/include/SenseSoar/mavlink_msg_sensesoar_mode_ack.h
+118
-0
mavlink_msg_sensesoar_mode_chng.h
...vlink/include/SenseSoar/mavlink_msg_sensesoar_mode_chng.h
+118
-0
mavlink_msg_sensesoar_mode_rqst.h
...vlink/include/SenseSoar/mavlink_msg_sensesoar_mode_rqst.h
+101
-0
mavlink_msg_sensesoar_mode_rqst_send.h
.../include/SenseSoar/mavlink_msg_sensesoar_mode_rqst_send.h
+101
-0
mavlink_msg_sys_stat.h
thirdParty/mavlink/include/SenseSoar/mavlink_msg_sys_stat.h
+152
-0
common.h
thirdParty/mavlink/include/common/common.h
+1
-1
mavlink.h
thirdParty/mavlink/include/common/mavlink.h
+1
-1
mavlink_types.h
thirdParty/mavlink/include/mavlink_types.h
+3
-1
SenseSoar.xml
thirdParty/mavlink/message_definitions/SenseSoar.xml
+99
-0
No files found.
.gitignore
View file @
241d6c36
...
...
@@ -51,3 +51,4 @@ user_config.pri
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
thirdParty/qserialport/lib/
thirdParty/libxbee/lib
qgroundcontrol.pro
View file @
241d6c36
...
...
@@ -118,6 +118,16 @@ contains(MAVLINK_CONF, ardupilotmega) {
INCLUDEPATH
+=
$$
BASEDIR
/
thirdParty
/
mavlink
/
include
/
ardupilotmega
DEFINES
+=
QGC_USE_ARDUPILOTMEGA_MESSAGES
}
contains
(
MAVLINK_CONF
,
senseSoar
)
{
#
Remove
the
default
set
-
it
is
included
anyway
INCLUDEPATH
-=
$$
BASEDIR
/../
mavlink
/
include
/
common
INCLUDEPATH
-=
$$
BASEDIR
/
thirdParty
/
mavlink
/
include
/
common
#
SENSESOAR
SPECIAL
MESSAGES
INCLUDEPATH
+=
$$
BASEDIR
/../
mavlink
/
include
/
SenseSoar
INCLUDEPATH
+=
$$
BASEDIR
/
thirdParty
/
mavlink
/
include
/
SenseSoar
DEFINES
+=
QGC_USE_SENSESOAR_MESSAGES
}
#
Include
general
settings
for
QGroundControl
...
...
thirdParty/mavlink/include/SenseSoar/SenseSoar.h
0 → 100644
View file @
241d6c36
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H
#ifdef __cplusplus
extern
"C"
{
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_SENSESOAR
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
/** @brief Different flight modes */
enum
SENSESOAR_MODE
{
SENSESOAR_MODE_GLIDING
=
0
,
/* */
SENSESOAR_MODE_AUTONOMOUS
=
1
,
/* */
SENSESOAR_MODE_MANUAL
=
2
,
/* */
SENSESOAR_MODE_ENUM_END
};
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensesoar_mode_chng.h"
#include "./mavlink_msg_sensesoar_mode_ack.h"
#include "./mavlink_msg_sensesoar_mode_rqst.h"
#include "./mavlink_msg_sensesoar_mode_rqst_send.h"
#include "./mavlink_msg_obs_position.h"
#include "./mavlink_msg_obs_velocity.h"
#include "./mavlink_msg_obs_attitude.h"
#include "./mavlink_msg_obs_wind.h"
#include "./mavlink_msg_obs_air_velocity.h"
#include "./mavlink_msg_obs_bias.h"
#include "./mavlink_msg_obs_qff.h"
#include "./mavlink_msg_obs_air_temp.h"
#include "./mavlink_msg_filt_rot_vel.h"
#include "./mavlink_msg_llc_out.h"
#include "./mavlink_msg_pm_elec.h"
#include "./mavlink_msg_sys_stat.h"
#include "./mavlink_msg_cmd_airspeed_chng.h"
#include "./mavlink_msg_cmd_airspeed_ack.h"
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 1, 1, 24, 0, 12, 0, 16, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#ifdef __cplusplus
}
#endif
#endif
thirdParty/mavlink/include/SenseSoar/mavlink.h
0 → 100644
View file @
241d6c36
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#include "SenseSoar.h"
#endif
thirdParty/mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_ack.h
0 → 100644
View file @
241d6c36
// MESSAGE CMD_AIRSPEED_ACK PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194
typedef
struct
__mavlink_cmd_airspeed_ack_t
{
float
spCmd
;
///< commanded airspeed
uint8_t
ack
;
///< 0:ack, 1:nack
}
mavlink_cmd_airspeed_ack_t
;
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_ack_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
float
spCmd
,
uint8_t
ack
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_CMD_AIRSPEED_ACK
;
i
+=
put_float_by_index
(
spCmd
,
i
,
msg
->
payload
);
// commanded airspeed
i
+=
put_uint8_t_by_index
(
ack
,
i
,
msg
->
payload
);
// 0:ack, 1:nack
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
i
);
}
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_ack_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
float
spCmd
,
uint8_t
ack
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_CMD_AIRSPEED_ACK
;
i
+=
put_float_by_index
(
spCmd
,
i
,
msg
->
payload
);
// commanded airspeed
i
+=
put_uint8_t_by_index
(
ack
,
i
,
msg
->
payload
);
// 0:ack, 1:nack
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
i
);
}
/**
* @brief Encode a cmd_airspeed_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_ack C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_ack_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_cmd_airspeed_ack_t
*
cmd_airspeed_ack
)
{
return
mavlink_msg_cmd_airspeed_ack_pack
(
system_id
,
component_id
,
msg
,
cmd_airspeed_ack
->
spCmd
,
cmd_airspeed_ack
->
ack
);
}
/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_cmd_airspeed_ack_send
(
mavlink_channel_t
chan
,
float
spCmd
,
uint8_t
ack
)
{
mavlink_message_t
msg
;
mavlink_msg_cmd_airspeed_ack_pack_chan
(
mavlink_system
.
sysid
,
mavlink_system
.
compid
,
chan
,
&
msg
,
spCmd
,
ack
);
mavlink_send_uart
(
chan
,
&
msg
);
}
#endif
// MESSAGE CMD_AIRSPEED_ACK UNPACKING
/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
*/
static
inline
float
mavlink_msg_cmd_airspeed_ack_get_spCmd
(
const
mavlink_message_t
*
msg
)
{
generic_32bit
r
;
r
.
b
[
3
]
=
(
msg
->
payload
)[
0
];
r
.
b
[
2
]
=
(
msg
->
payload
)[
1
];
r
.
b
[
1
]
=
(
msg
->
payload
)[
2
];
r
.
b
[
0
]
=
(
msg
->
payload
)[
3
];
return
(
float
)
r
.
f
;
}
/**
* @brief Get field ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
*/
static
inline
uint8_t
mavlink_msg_cmd_airspeed_ack_get_ack
(
const
mavlink_message_t
*
msg
)
{
return
(
uint8_t
)(
msg
->
payload
+
sizeof
(
float
))[
0
];
}
/**
* @brief Decode a cmd_airspeed_ack message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_ack C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_cmd_airspeed_ack_decode
(
const
mavlink_message_t
*
msg
,
mavlink_cmd_airspeed_ack_t
*
cmd_airspeed_ack
)
{
cmd_airspeed_ack
->
spCmd
=
mavlink_msg_cmd_airspeed_ack_get_spCmd
(
msg
);
cmd_airspeed_ack
->
ack
=
mavlink_msg_cmd_airspeed_ack_get_ack
(
msg
);
}
thirdParty/mavlink/include/SenseSoar/mavlink_msg_cmd_airspeed_chng.h
0 → 100644
View file @
241d6c36
// MESSAGE CMD_AIRSPEED_CHNG PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192
typedef
struct
__mavlink_cmd_airspeed_chng_t
{
uint8_t
target
;
///< Target ID
float
spCmd
;
///< commanded airspeed
}
mavlink_cmd_airspeed_chng_t
;
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_chng_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
uint8_t
target
,
float
spCmd
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG
;
i
+=
put_uint8_t_by_index
(
target
,
i
,
msg
->
payload
);
// Target ID
i
+=
put_float_by_index
(
spCmd
,
i
,
msg
->
payload
);
// commanded airspeed
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
i
);
}
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_chng_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
uint8_t
target
,
float
spCmd
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG
;
i
+=
put_uint8_t_by_index
(
target
,
i
,
msg
->
payload
);
// Target ID
i
+=
put_float_by_index
(
spCmd
,
i
,
msg
->
payload
);
// commanded airspeed
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
i
);
}
/**
* @brief Encode a cmd_airspeed_chng struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_chng C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_cmd_airspeed_chng_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_cmd_airspeed_chng_t
*
cmd_airspeed_chng
)
{
return
mavlink_msg_cmd_airspeed_chng_pack
(
system_id
,
component_id
,
msg
,
cmd_airspeed_chng
->
target
,
cmd_airspeed_chng
->
spCmd
);
}
/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_cmd_airspeed_chng_send
(
mavlink_channel_t
chan
,
uint8_t
target
,
float
spCmd
)
{
mavlink_message_t
msg
;
mavlink_msg_cmd_airspeed_chng_pack_chan
(
mavlink_system
.
sysid
,
mavlink_system
.
compid
,
chan
,
&
msg
,
target
,
spCmd
);
mavlink_send_uart
(
chan
,
&
msg
);
}
#endif
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING
/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
*/
static
inline
uint8_t
mavlink_msg_cmd_airspeed_chng_get_target
(
const
mavlink_message_t
*
msg
)
{
return
(
uint8_t
)(
msg
->
payload
)[
0
];
}
/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
*/
static
inline
float
mavlink_msg_cmd_airspeed_chng_get_spCmd
(
const
mavlink_message_t
*
msg
)
{
generic_32bit
r
;
r
.
b
[
3
]
=
(
msg
->
payload
+
sizeof
(
uint8_t
))[
0
];
r
.
b
[
2
]
=
(
msg
->
payload
+
sizeof
(
uint8_t
))[
1
];
r
.
b
[
1
]
=
(
msg
->
payload
+
sizeof
(
uint8_t
))[
2
];
r
.
b
[
0
]
=
(
msg
->
payload
+
sizeof
(
uint8_t
))[
3
];
return
(
float
)
r
.
f
;
}
/**
* @brief Decode a cmd_airspeed_chng message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_chng C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_cmd_airspeed_chng_decode
(
const
mavlink_message_t
*
msg
,
mavlink_cmd_airspeed_chng_t
*
cmd_airspeed_chng
)
{
cmd_airspeed_chng
->
target
=
mavlink_msg_cmd_airspeed_chng_get_target
(
msg
);
cmd_airspeed_chng
->
spCmd
=
mavlink_msg_cmd_airspeed_chng_get_spCmd
(
msg
);
}
thirdParty/mavlink/include/SenseSoar/mavlink_msg_filt_rot_vel.h
0 → 100644
View file @
241d6c36
// MESSAGE FILT_ROT_VEL PACKING
#define MAVLINK_MSG_ID_FILT_ROT_VEL 184
typedef
struct
__mavlink_filt_rot_vel_t
{
float
rotVel
[
3
];
///< rotational velocity
}
mavlink_filt_rot_vel_t
;
#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_filt_rot_vel_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
float
*
rotVel
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_FILT_ROT_VEL
;
i
+=
put_array_by_index
((
const
int8_t
*
)
rotVel
,
sizeof
(
float
)
*
3
,
i
,
msg
->
payload
);
// rotational velocity
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
i
);
}
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_filt_rot_vel_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
const
float
*
rotVel
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_FILT_ROT_VEL
;
i
+=
put_array_by_index
((
const
int8_t
*
)
rotVel
,
sizeof
(
float
)
*
3
,
i
,
msg
->
payload
);
// rotational velocity
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
i
);
}
/**
* @brief Encode a filt_rot_vel struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param filt_rot_vel C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_filt_rot_vel_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_filt_rot_vel_t
*
filt_rot_vel
)
{
return
mavlink_msg_filt_rot_vel_pack
(
system_id
,
component_id
,
msg
,
filt_rot_vel
->
rotVel
);
}
/**
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
*
* @param rotVel rotational velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_filt_rot_vel_send
(
mavlink_channel_t
chan
,
const
float
*
rotVel
)
{
mavlink_message_t
msg
;
mavlink_msg_filt_rot_vel_pack_chan
(
mavlink_system
.
sysid
,
mavlink_system
.
compid
,
chan
,
&
msg
,
rotVel
);
mavlink_send_uart
(
chan
,
&
msg
);
}
#endif
// MESSAGE FILT_ROT_VEL UNPACKING
/**
* @brief Get field rotVel from filt_rot_vel message
*
* @return rotational velocity
*/
static
inline
uint16_t
mavlink_msg_filt_rot_vel_get_rotVel
(
const
mavlink_message_t
*
msg
,
float
*
r_data
)
{
memcpy
(
r_data
,
msg
->
payload
,
sizeof
(
float
)
*
3
);
return
sizeof
(
float
)
*
3
;
}
/**
* @brief Decode a filt_rot_vel message into a struct
*
* @param msg The message to decode
* @param filt_rot_vel C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_filt_rot_vel_decode
(
const
mavlink_message_t
*
msg
,
mavlink_filt_rot_vel_t
*
filt_rot_vel
)
{
mavlink_msg_filt_rot_vel_get_rotVel
(
msg
,
filt_rot_vel
->
rotVel
);
}
thirdParty/mavlink/include/SenseSoar/mavlink_msg_llc_out.h
0 → 100644
View file @
241d6c36
// MESSAGE LLC_OUT PACKING
#define MAVLINK_MSG_ID_LLC_OUT 186
typedef
struct
__mavlink_llc_out_t
{
int16_t
servoOut
[
4
];
///< Servo signal
int16_t
MotorOut
[
2
];
///< motor signal
}
mavlink_llc_out_t
;
#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4
#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_llc_out_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
int16_t
*
servoOut
,
const
int16_t
*
MotorOut
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_LLC_OUT
;
i
+=
put_array_by_index
((
const
int8_t
*
)
servoOut
,
sizeof
(
int16_t
)
*
4
,
i
,
msg
->
payload
);
// Servo signal
i
+=
put_array_by_index
((
const
int8_t
*
)
MotorOut
,
sizeof
(
int16_t
)
*
2
,
i
,
msg
->
payload
);
// motor signal
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
i
);
}
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_llc_out_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
const
int16_t
*
servoOut
,
const
int16_t
*
MotorOut
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_LLC_OUT
;
i
+=
put_array_by_index
((
const
int8_t
*
)
servoOut
,
sizeof
(
int16_t
)
*
4
,
i
,
msg
->
payload
);
// Servo signal
i
+=
put_array_by_index
((
const
int8_t
*
)
MotorOut
,
sizeof
(
int16_t
)
*
2
,
i
,
msg
->
payload
);
// motor signal
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
i
);
}
/**
* @brief Encode a llc_out struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param llc_out C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_llc_out_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_llc_out_t
*
llc_out
)
{
return
mavlink_msg_llc_out_pack
(
system_id
,
component_id
,
msg
,
llc_out
->
servoOut
,
llc_out
->
MotorOut
);
}
/**
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
*
* @param servoOut Servo signal
* @param MotorOut motor signal
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_llc_out_send
(
mavlink_channel_t
chan
,
const
int16_t
*
servoOut
,
const
int16_t
*
MotorOut
)
{
mavlink_message_t
msg
;
mavlink_msg_llc_out_pack_chan
(
mavlink_system
.
sysid
,
mavlink_system
.
compid
,
chan
,
&
msg
,
servoOut
,
MotorOut
);
mavlink_send_uart
(
chan
,
&
msg
);
}
#endif
// MESSAGE LLC_OUT UNPACKING
/**
* @brief Get field servoOut from llc_out message
*
* @return Servo signal
*/
static
inline
uint16_t
mavlink_msg_llc_out_get_servoOut
(
const
mavlink_message_t
*
msg
,
int16_t
*
r_data
)
{
memcpy
(
r_data
,
msg
->
payload
,
sizeof
(
int16_t
)
*
4
);
return
sizeof
(
int16_t
)
*
4
;
}
/**
* @brief Get field MotorOut from llc_out message
*
* @return motor signal
*/
static
inline
uint16_t
mavlink_msg_llc_out_get_MotorOut
(
const
mavlink_message_t
*
msg
,
int16_t
*
r_data
)
{
memcpy
(
r_data
,
msg
->
payload
+
sizeof
(
int16_t
)
*
4
,
sizeof
(
int16_t
)
*
2
);
return
sizeof
(
int16_t
)
*
2
;
}
/**
* @brief Decode a llc_out message into a struct
*
* @param msg The message to decode
* @param llc_out C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_llc_out_decode
(
const
mavlink_message_t
*
msg
,
mavlink_llc_out_t
*
llc_out
)
{
mavlink_msg_llc_out_get_servoOut
(
msg
,
llc_out
->
servoOut
);
mavlink_msg_llc_out_get_MotorOut
(
msg
,
llc_out
->
MotorOut
);
}
thirdParty/mavlink/include/SenseSoar/mavlink_msg_obs_air_temp.h
0 → 100644
View file @
241d6c36
// MESSAGE OBS_AIR_TEMP PACKING
#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183
typedef
struct
__mavlink_obs_air_temp_t
{
float
airT
;
///< Air Temperatur
}
mavlink_obs_air_temp_t
;
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_obs_air_temp_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
float
airT
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_OBS_AIR_TEMP
;
i
+=
put_float_by_index
(
airT
,
i
,
msg
->
payload
);
// Air Temperatur
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
i
);
}
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_obs_air_temp_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
float
airT
)
{
uint16_t
i
=
0
;
msg
->
msgid
=
MAVLINK_MSG_ID_OBS_AIR_TEMP
;
i
+=
put_float_by_index
(
airT
,
i
,
msg
->
payload
);
// Air Temperatur
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
i
);
}
/**
* @brief Encode a obs_air_temp struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_temp C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_obs_air_temp_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_obs_air_temp_t
*
obs_air_temp
)
{
return
mavlink_msg_obs_air_temp_pack
(
system_id
,
component_id
,
msg
,
obs_air_temp
->
airT
);
}
/**
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
*
* @param airT Air Temperatur
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_obs_air_temp_send
(
mavlink_channel_t
chan
,
float
airT
)
{
mavlink_message_t
msg
;
mavlink_msg_obs_air_temp_pack_chan
(
mavlink_system
.
sysid
,
mavlink_system
.
compid
,
chan
,
&
msg
,
airT
);
mavlink_send_uart
(
chan
,
&
msg
);
}
#endif
// MESSAGE OBS_AIR_TEMP UNPACKING
/**
* @brief Get field airT from obs_air_temp message
*
* @return Air Temperatur
*/
static
inline
float
mavlink_msg_obs_air_temp_get_airT
(
const
mavlink_message_t
*
msg
)
{
generic_32bit
r
;
r
.
b
[
3
]
=
(
msg
->
payload
)[
0
];
r
.
b
[
2
]
=
(
msg
->
payload
)[
1
];
r
.
b
[
1
]
=
(
msg
->
payload
)[
2
];
r
.
b
[
0
]
=
(
msg
->
payload
)[
3
];
return
(
float
)
r
.
f
;
}
/**
* @brief Decode a obs_air_temp message into a struct
*
* @param msg The message to decode
* @param obs_air_temp C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_obs_air_temp_decode
(
const
mavlink_message_t
*
msg
,
mavlink_obs_air_temp_t
*
obs_air_temp
)
{
obs_air_temp
->
airT
=
mavlink_msg_obs_air_temp_get_airT
(
msg
);
}
thirdParty/mavlink/include/SenseSoar/mavlink_msg_obs_air_velocity.h
0 → 100644
View file @
241d6c36
// MESSAGE OBS_AIR_VELOCITY PACKING