mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
ACM : formatting
This commit is contained in:
parent
5cb5618814
commit
d2a0913b2d
@ -305,6 +305,7 @@ AP_AHRS_HIL ahrs(&ins, g_gps);
|
|||||||
AP_GPS_HIL g_gps_driver(NULL);
|
AP_GPS_HIL g_gps_driver(NULL);
|
||||||
AP_Compass_HIL compass; // never used
|
AP_Compass_HIL compass; // never used
|
||||||
AP_Baro_BMP085_HIL barometer;
|
AP_Baro_BMP085_HIL barometer;
|
||||||
|
|
||||||
#ifdef OPTFLOW_ENABLED
|
#ifdef OPTFLOW_ENABLED
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||||
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
|
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
|
||||||
@ -932,15 +933,10 @@ AP_Mount camera_mount2(¤t_loc, g_gps, &ahrs, 1);
|
|||||||
// Experimental AP_Limits library - set constraints, limits, fences, minima, maxima on various parameters
|
// Experimental AP_Limits library - set constraints, limits, fences, minima, maxima on various parameters
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
#ifdef AP_LIMITS
|
#ifdef AP_LIMITS
|
||||||
|
|
||||||
AP_Limits limits;
|
AP_Limits limits;
|
||||||
|
|
||||||
AP_Limit_GPSLock gpslock_limit(g_gps);
|
AP_Limit_GPSLock gpslock_limit(g_gps);
|
||||||
|
|
||||||
AP_Limit_Geofence geofence_limit(FENCE_START_BYTE, FENCE_WP_SIZE, MAX_FENCEPOINTS, g_gps, &home, ¤t_loc);
|
AP_Limit_Geofence geofence_limit(FENCE_START_BYTE, FENCE_WP_SIZE, MAX_FENCEPOINTS, g_gps, &home, ¤t_loc);
|
||||||
|
|
||||||
AP_Limit_Altitude altitude_limit(¤t_loc);
|
AP_Limit_Altitude altitude_limit(¤t_loc);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
Loading…
Reference in New Issue
Block a user