mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 00:48:30 -04:00
d31896a545
* Implement frame ID checking and test it * Implement the visual odom function that does narrowing to floats * Normalize quaternions from ROS * Supply 0 error to EKF * Handle external odomo only if HAL_VISUALODOM_ENABLED is defined * Implement odom timestamping and improve docs * Add unit tests * Add a CONFIG file for DDS Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
18 lines
414 B
C
18 lines
414 B
C
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
#ifndef AP_DDS_ENABLED
|
|
#define AP_DDS_ENABLED 1
|
|
#endif
|
|
|
|
// UDP only on SITL for now
|
|
#ifndef AP_DDS_UDP_ENABLED
|
|
#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
|
#endif
|
|
|
|
#include <AP_VisualOdom/AP_VisualOdom_config.h>
|
|
#ifndef AP_DDS_VISUALODOM_ENABLED
|
|
#define AP_DDS_VISUALODOM_ENABLED HAL_VISUALODOM_ENABLED && AP_DDS_ENABLED
|
|
#endif
|