Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
C
C-Astral dialect C library
Project overview
Project overview
Details
Activity
Releases
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Analytics
Analytics
CI / CD
Repository
Value Stream
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
nexedi
C-Astral dialect C library
Commits
023e64d2
Commit
023e64d2
authored
Oct 26, 2021
by
Léo-Paul Géneau
👾
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add gps time
parent
94af4a57
Changes
5
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
278 additions
and
9 deletions
+278
-9
CAstral/CAstral.h
CAstral/CAstral.h
+4
-3
CAstral/mavlink_msg_cap_status.h
CAstral/mavlink_msg_cap_status.h
+5
-5
CAstral/mavlink_msg_cap_status_frequent.h
CAstral/mavlink_msg_cap_status_frequent.h
+213
-0
CAstral/testsuite.h
CAstral/testsuite.h
+55
-0
CAstral/version.h
CAstral/version.h
+1
-1
No files found.
CAstral/CAstral.h
View file @
023e64d2
This diff is collapsed.
Click to expand it.
CAstral/mavlink_msg_cap_status.h
View file @
023e64d2
...
...
@@ -11,7 +11,7 @@ typedef struct __mavlink_cap_status_t {
uint32_t
global_status
;
/*< 0-airspeed-cal, 1-parachute, 2-home init, 3-landed, 4-speed override, 5-altitude ovveride, 6-battery low, 7-battery critical, 8-falsafe, 9-failsafe rc loss, 10-failsafe GPS loss, 11-failsafe data link loss, 12-failsafe mission, 13-failsafe offboard loss, 14-failsafe loss of control, 15-failsafe_min_agl, 16 - failsafe_crit_agl, 17 - terrain failsafe enabled, 18 - altitude override type, 19 - speed override type, 20 - gimbal extended*/
float
speed_override_value
;
/*< Speed override value*/
uint32_t
flightplan_hash
;
/*< Flightplan hash*/
float
baro_altitude
;
/*< Baro altitude value*/
float
baro_altitude
;
/*< Baro
meter
altitude value*/
float
eph
;
/*< Standard deviation of horizontal position error, (metres)*/
float
epv
;
/*< Standard deviation of vertical position error, (metres)*/
uint16_t
number_of_photos
;
/*< Number of photos taken in a mission*/
...
...
@@ -99,7 +99,7 @@ typedef struct __mavlink_cap_status_t {
* @param speed_override_value Speed override value
* @param flightplan_hash Flightplan hash
* @param flightplan_items_count Flightplan Items Count
* @param baro_altitude Baro altitude value
* @param baro_altitude Baro
meter
altitude value
* @param eph Standard deviation of horizontal position error, (metres)
* @param epv Standard deviation of vertical position error, (metres)
* @return length of the message in bytes (excluding serial stream start sign)
...
...
@@ -172,7 +172,7 @@ static inline uint16_t mavlink_msg_cap_status_pack(uint8_t system_id, uint8_t co
* @param speed_override_value Speed override value
* @param flightplan_hash Flightplan hash
* @param flightplan_items_count Flightplan Items Count
* @param baro_altitude Baro altitude value
* @param baro_altitude Baro
meter
altitude value
* @param eph Standard deviation of horizontal position error, (metres)
* @param epv Standard deviation of vertical position error, (metres)
* @return length of the message in bytes (excluding serial stream start sign)
...
...
@@ -271,7 +271,7 @@ static inline uint16_t mavlink_msg_cap_status_encode_chan(uint8_t system_id, uin
* @param speed_override_value Speed override value
* @param flightplan_hash Flightplan hash
* @param flightplan_items_count Flightplan Items Count
* @param baro_altitude Baro altitude value
* @param baro_altitude Baro
meter
altitude value
* @param eph Standard deviation of horizontal position error, (metres)
* @param epv Standard deviation of vertical position error, (metres)
*/
...
...
@@ -528,7 +528,7 @@ static inline uint16_t mavlink_msg_cap_status_get_flightplan_items_count(const m
/**
* @brief Get field baro_altitude from cap_status message
*
* @return Baro altitude value
* @return Baro
meter
altitude value
*/
static
inline
float
mavlink_msg_cap_status_get_baro_altitude
(
const
mavlink_message_t
*
msg
)
{
...
...
CAstral/mavlink_msg_cap_status_frequent.h
0 → 100644
View file @
023e64d2
#pragma once
// MESSAGE CAP_STATUS_FREQUENT PACKING
#define MAVLINK_MSG_ID_CAP_STATUS_FREQUENT 185
typedef
struct
__mavlink_cap_status_frequent_t
{
uint64_t
utc_time
;
/*< UTC time reported by the GPS.*/
}
mavlink_cap_status_frequent_t
;
#define MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN 8
#define MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN 8
#define MAVLINK_MSG_ID_185_LEN 8
#define MAVLINK_MSG_ID_185_MIN_LEN 8
#define MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC 93
#define MAVLINK_MSG_ID_185_CRC 93
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAP_STATUS_FREQUENT { \
185, \
"CAP_STATUS_FREQUENT", \
1, \
{ { "utc_time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_cap_status_frequent_t, utc_time) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAP_STATUS_FREQUENT { \
"CAP_STATUS_FREQUENT", \
1, \
{ { "utc_time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_cap_status_frequent_t, utc_time) }, \
} \
}
#endif
/**
* @brief Pack a cap_status_frequent 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 utc_time UTC time reported by the GPS.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cap_status_frequent_pack
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
uint64_t
utc_time
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char
buf
[
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
];
_mav_put_uint64_t
(
buf
,
0
,
utc_time
);
memcpy
(
_MAV_PAYLOAD_NON_CONST
(
msg
),
buf
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
);
#else
mavlink_cap_status_frequent_t
packet
;
packet
.
utc_time
=
utc_time
;
memcpy
(
_MAV_PAYLOAD_NON_CONST
(
msg
),
&
packet
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
);
#endif
msg
->
msgid
=
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
;
return
mavlink_finalize_message
(
msg
,
system_id
,
component_id
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
}
/**
* @brief Pack a cap_status_frequent message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param utc_time UTC time reported by the GPS.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static
inline
uint16_t
mavlink_msg_cap_status_frequent_pack_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
uint64_t
utc_time
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char
buf
[
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
];
_mav_put_uint64_t
(
buf
,
0
,
utc_time
);
memcpy
(
_MAV_PAYLOAD_NON_CONST
(
msg
),
buf
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
);
#else
mavlink_cap_status_frequent_t
packet
;
packet
.
utc_time
=
utc_time
;
memcpy
(
_MAV_PAYLOAD_NON_CONST
(
msg
),
&
packet
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
);
#endif
msg
->
msgid
=
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
;
return
mavlink_finalize_message_chan
(
msg
,
system_id
,
component_id
,
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
}
/**
* @brief Encode a cap_status_frequent struct
*
* @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 cap_status_frequent C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_cap_status_frequent_encode
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
msg
,
const
mavlink_cap_status_frequent_t
*
cap_status_frequent
)
{
return
mavlink_msg_cap_status_frequent_pack
(
system_id
,
component_id
,
msg
,
cap_status_frequent
->
utc_time
);
}
/**
* @brief Encode a cap_status_frequent struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param cap_status_frequent C-struct to read the message contents from
*/
static
inline
uint16_t
mavlink_msg_cap_status_frequent_encode_chan
(
uint8_t
system_id
,
uint8_t
component_id
,
uint8_t
chan
,
mavlink_message_t
*
msg
,
const
mavlink_cap_status_frequent_t
*
cap_status_frequent
)
{
return
mavlink_msg_cap_status_frequent_pack_chan
(
system_id
,
component_id
,
chan
,
msg
,
cap_status_frequent
->
utc_time
);
}
/**
* @brief Send a cap_status_frequent message
* @param chan MAVLink channel to send the message
*
* @param utc_time UTC time reported by the GPS.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static
inline
void
mavlink_msg_cap_status_frequent_send
(
mavlink_channel_t
chan
,
uint64_t
utc_time
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char
buf
[
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
];
_mav_put_uint64_t
(
buf
,
0
,
utc_time
);
_mav_finalize_message_chan_send
(
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
,
buf
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
#else
mavlink_cap_status_frequent_t
packet
;
packet
.
utc_time
=
utc_time
;
_mav_finalize_message_chan_send
(
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
,
(
const
char
*
)
&
packet
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
#endif
}
/**
* @brief Send a cap_status_frequent message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static
inline
void
mavlink_msg_cap_status_frequent_send_struct
(
mavlink_channel_t
chan
,
const
mavlink_cap_status_frequent_t
*
cap_status_frequent
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_cap_status_frequent_send
(
chan
,
cap_status_frequent
->
utc_time
);
#else
_mav_finalize_message_chan_send
(
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
,
(
const
char
*
)
cap_status_frequent
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
#endif
}
#if MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static
inline
void
mavlink_msg_cap_status_frequent_send_buf
(
mavlink_message_t
*
msgbuf
,
mavlink_channel_t
chan
,
uint64_t
utc_time
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char
*
buf
=
(
char
*
)
msgbuf
;
_mav_put_uint64_t
(
buf
,
0
,
utc_time
);
_mav_finalize_message_chan_send
(
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
,
buf
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
#else
mavlink_cap_status_frequent_t
*
packet
=
(
mavlink_cap_status_frequent_t
*
)
msgbuf
;
packet
->
utc_time
=
utc_time
;
_mav_finalize_message_chan_send
(
chan
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
,
(
const
char
*
)
packet
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_CRC
);
#endif
}
#endif
#endif
// MESSAGE CAP_STATUS_FREQUENT UNPACKING
/**
* @brief Get field utc_time from cap_status_frequent message
*
* @return UTC time reported by the GPS.
*/
static
inline
uint64_t
mavlink_msg_cap_status_frequent_get_utc_time
(
const
mavlink_message_t
*
msg
)
{
return
_MAV_RETURN_uint64_t
(
msg
,
0
);
}
/**
* @brief Decode a cap_status_frequent message into a struct
*
* @param msg The message to decode
* @param cap_status_frequent C-struct to decode the message contents into
*/
static
inline
void
mavlink_msg_cap_status_frequent_decode
(
const
mavlink_message_t
*
msg
,
mavlink_cap_status_frequent_t
*
cap_status_frequent
)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
cap_status_frequent
->
utc_time
=
mavlink_msg_cap_status_frequent_get_utc_time
(
msg
);
#else
uint8_t
len
=
msg
->
len
<
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
?
msg
->
len
:
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
;
memset
(
cap_status_frequent
,
0
,
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_LEN
);
memcpy
(
cap_status_frequent
,
_MAV_PAYLOAD
(
msg
),
len
);
#endif
}
CAstral/testsuite.h
View file @
023e64d2
...
...
@@ -7395,6 +7395,60 @@ static void mavlink_test_terrain_elevation(uint8_t system_id, uint8_t component_
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
}
static
void
mavlink_test_cap_status_frequent
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
last_msg
)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t
*
status
=
mavlink_get_channel_status
(
MAVLINK_COMM_0
);
if
((
status
->
flags
&
MAVLINK_STATUS_FLAG_OUT_MAVLINK1
)
&&
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT
>=
256
)
{
return
;
}
#endif
mavlink_message_t
msg
;
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
uint16_t
i
;
mavlink_cap_status_frequent_t
packet_in
=
{
93372036854775807ULL
};
mavlink_cap_status_frequent_t
packet1
,
packet2
;
memset
(
&
packet1
,
0
,
sizeof
(
packet1
));
packet1
.
utc_time
=
packet_in
.
utc_time
;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if
(
status
->
flags
&
MAVLINK_STATUS_FLAG_OUT_MAVLINK1
)
{
// cope with extensions
memset
(
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
+
(
char
*
)
&
packet1
,
0
,
sizeof
(
packet1
)
-
MAVLINK_MSG_ID_CAP_STATUS_FREQUENT_MIN_LEN
);
}
#endif
memset
(
&
packet2
,
0
,
sizeof
(
packet2
));
mavlink_msg_cap_status_frequent_encode
(
system_id
,
component_id
,
&
msg
,
&
packet1
);
mavlink_msg_cap_status_frequent_decode
(
&
msg
,
&
packet2
);
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
memset
(
&
packet2
,
0
,
sizeof
(
packet2
));
mavlink_msg_cap_status_frequent_pack
(
system_id
,
component_id
,
&
msg
,
packet1
.
utc_time
);
mavlink_msg_cap_status_frequent_decode
(
&
msg
,
&
packet2
);
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
memset
(
&
packet2
,
0
,
sizeof
(
packet2
));
mavlink_msg_cap_status_frequent_pack_chan
(
system_id
,
component_id
,
MAVLINK_COMM_0
,
&
msg
,
packet1
.
utc_time
);
mavlink_msg_cap_status_frequent_decode
(
&
msg
,
&
packet2
);
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
memset
(
&
packet2
,
0
,
sizeof
(
packet2
));
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
for
(
i
=
0
;
i
<
mavlink_msg_get_send_buffer_length
(
&
msg
);
i
++
)
{
comm_send_ch
(
MAVLINK_COMM_0
,
buffer
[
i
]);
}
mavlink_msg_cap_status_frequent_decode
(
last_msg
,
&
packet2
);
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
memset
(
&
packet2
,
0
,
sizeof
(
packet2
));
mavlink_msg_cap_status_frequent_send
(
MAVLINK_COMM_1
,
packet1
.
utc_time
);
mavlink_msg_cap_status_frequent_decode
(
last_msg
,
&
packet2
);
MAVLINK_ASSERT
(
memcmp
(
&
packet1
,
&
packet2
,
sizeof
(
packet1
))
==
0
);
}
static
void
mavlink_test_estimator_status
(
uint8_t
system_id
,
uint8_t
component_id
,
mavlink_message_t
*
last_msg
)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
...
...
@@ -8663,6 +8717,7 @@ static void mavlink_test_CAstral(uint8_t system_id, uint8_t component_id, mavlin
mavlink_test_serial_passthrough_ack
(
system_id
,
component_id
,
last_msg
);
mavlink_test_mission_hash
(
system_id
,
component_id
,
last_msg
);
mavlink_test_terrain_elevation
(
system_id
,
component_id
,
last_msg
);
mavlink_test_cap_status_frequent
(
system_id
,
component_id
,
last_msg
);
mavlink_test_estimator_status
(
system_id
,
component_id
,
last_msg
);
mavlink_test_wind_cov
(
system_id
,
component_id
,
last_msg
);
mavlink_test_gps_input
(
system_id
,
component_id
,
last_msg
);
...
...
CAstral/version.h
View file @
023e64d2
...
...
@@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "
Fri Mar
26 2021"
#define MAVLINK_BUILD_DATE "
Tue Oct
26 2021"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment