From 6fc94828b856632d4d07397fe464a1d702d8a93e Mon Sep 17 00:00:00 2001 From: uncrustify Date: Thu, 16 Aug 2012 23:20:06 -0700 Subject: [PATCH] uncrustify libraries/AP_Limits/AP_Limit_Geofence.h --- libraries/AP_Limits/AP_Limit_Geofence.h | 56 ++++++++++++------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/libraries/AP_Limits/AP_Limit_Geofence.h b/libraries/AP_Limits/AP_Limit_Geofence.h index 52bc3bc2e5..08007528cd 100644 --- a/libraries/AP_Limits/AP_Limit_Geofence.h +++ b/libraries/AP_Limits/AP_Limit_Geofence.h @@ -13,59 +13,59 @@ #include #ifndef AP_Limit_Geofence_H -#define AP_Limit_Geofence_H + #define AP_Limit_Geofence_H #endif // AP_Limit_Geofence_H #ifndef GPS_h -#include + #include #endif #define MAX_FENCEPOINTS 20 -class AP_Limit_Geofence: public AP_Limit_Module { +class AP_Limit_Geofence : public AP_Limit_Module { public: - AP_Limit_Geofence(uint32_t _eeprom_fence_start, uint8_t fpsize, uint8_t max_fp, GPS *&gps, struct Location *home_loc, struct Location *current_loc); - bool init(); - bool triggered(); + AP_Limit_Geofence(uint32_t _eeprom_fence_start, uint8_t fpsize, uint8_t max_fp, GPS *&gps, struct Location *home_loc, struct Location *current_loc); + bool init(); + bool triggered(); - AP_Int8 fence_total(); - void set_fence_point_with_index(Vector2l &point, uint8_t i); - Vector2l get_fence_point_with_index(uint8_t i); - void update_boundary(); - bool boundary_correct(); + AP_Int8 fence_total(); + void set_fence_point_with_index(Vector2l &point, uint8_t i); + Vector2l get_fence_point_with_index(uint8_t i); + void update_boundary(); + bool boundary_correct(); - static const struct AP_Param::GroupInfo var_info[]; + static const struct AP_Param::GroupInfo var_info[]; protected: - // pointers to gps, current location and home - GPS *&_gps; - struct Location *_current_loc; - struct Location *_home; + // pointers to gps, current location and home + GPS *& _gps; + struct Location * _current_loc; + struct Location * _home; - // Simple mode, just radius - AP_Int8 _simple; // 1 = simple, 0 = complex - AP_Int16 _radius; // in meters, for simple mode + // Simple mode, just radius + AP_Int8 _simple; // 1 = simple, 0 = complex + AP_Int16 _radius; // in meters, for simple mode - // Complex mode, defined fence points - AP_Int8 _fence_total; - AP_Int8 _num_points; + // Complex mode, defined fence points + AP_Int8 _fence_total; + AP_Int8 _num_points; private: - const uint32_t _eeprom_fence_start; - const unsigned _fence_wp_size; - const unsigned _max_fence_points; - bool _boundary_uptodate; - Vector2l _boundary[MAX_FENCEPOINTS]; // complex mode fence + const uint32_t _eeprom_fence_start; + const unsigned _fence_wp_size; + const unsigned _max_fence_points; + bool _boundary_uptodate; + Vector2l _boundary[MAX_FENCEPOINTS]; // complex mode fence }; // Helper functions -uint32_t get_distance_meters(struct Location *loc1, struct Location *loc2); // distance in meters between two locations +uint32_t get_distance_meters(struct Location *loc1, struct Location *loc2); // distance in meters between two locations