25 #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID 0x0001 26 #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID 0x0002 27 #define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID 0x0004 28 #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID 0x0011 29 #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID 0x0012 33 #define MM_DEBUG_LEVEL 0 37 #define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0) 39 #define Debug(level, fmt, args ...) 46 if (
uart !=
nullptr) {
67 uint16_t crc = 0xFFFF;
68 for (uint16_t pos = 0; pos < len; pos++) {
69 crc ^= (uint16_t) buf[pos];
70 for (uint8_t i = 8; i != 0; i--) {
71 if ((crc & 0x0001) != 0) {
123 for (uint8_t i = 0; i < n_used; i++) {
143 for (uint8_t i = 0; i < n; i++) {
144 const uint8_t ofs = 6 + i * 8;
153 if (stationary_beacon !=
nullptr) {
154 stationary_beacon->
address = address;
155 stationary_beacon->
x__mm = x * 10;
156 stationary_beacon->
y__mm = y * 10;
157 stationary_beacon->
z__mm = z * 10;
173 for (uint8_t i = 0; i < n; i++) {
174 const uint8_t ofs = 6 + i * 14;
189 if (stationary_beacon !=
nullptr) {
190 stationary_beacon->
address = address;
191 stationary_beacon->
x__mm =
x;
192 stationary_beacon->
y__mm = y;
193 stationary_beacon->
z__mm = z;
209 const uint8_t ofs = 6 + i * 6;
212 if (instance != -1) {
240 if (
uart ==
nullptr) {
245 uint8_t received_char = 0;
246 if (num_bytes_read < 0) {
249 while (num_bytes_read-- > 0) {
250 bool good_byte =
false;
257 good_byte = (received_char == 0xff);
260 good_byte = (received_char == 0x47);
276 good_byte = (received_char == 0x10);
285 good_byte = (received_char == 0x16);
310 if (block_crc == 0) {
380 "Hedge is at N%.2f, E%.2f, D%.2f",
394 "Beacon %d is at N%.2f, E%.2f, D%.2f",
412 bool swapped =
false;
418 for (uint8_t i = 1; i < j; i++) {
uint8_t input_buffer[AP_BEACON_MARVELMIND_BUF_SIZE]
bool vehicle_position_initialized
#define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID
uint16_t calc_crc_modbus(uint8_t *buf, uint16_t len)
static AP_SerialManager serial_manager
enum AP_Beacon_Marvelmind::@13 parse_state
Vector3< float > Vector3f
StationaryBeaconPosition beacons[AP_BEACON_MAX_BEACONS]
AP_Beacon_Marvelmind(AP_Beacon &frontend, AP_SerialManager &serial_manager)
void process_beacons_distances_datagram()
void set_stationary_beacons_positions()
void set_beacon_distance(uint8_t beacon_instance, float distance)
virtual void begin(uint32_t baud)=0
Interface definition for the various Ground Control System.
bool beacon_position_initialized
#define Debug(level, fmt, args ...)
#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID
#define AP_BEACON_MAX_BEACONS
void process_beacons_positions_datagram()
StationaryBeaconPosition * get_or_alloc_beacon(uint8_t address)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
uint16_t num_bytes_in_block_received
PositionValue cur_position
Vector3f beacon_position_NED__m[AP_BEACON_MAX_BEACONS]
#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID
#define AP_BEACON_TIMEOUT_MS
#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
void order_stationary_beacons()
void process_beacons_positions_highres_datagram()
virtual uint32_t available()=0
AP_HAL::UARTDriver * uart
void process_position_highres_datagram()
#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID
Vector3f vehicle_position_NED__m
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
StationaryBeaconsPositions positions_beacons
int8_t find_beacon_instance(uint8_t address) const
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
void process_position_datagram()