AC_PolyFence_loader.cpp 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. #include "AC_PolyFence_loader.h"
  2. extern const AP_HAL::HAL& hal;
  3. static const StorageAccess fence_storage(StorageManager::StorageFence);
  4. /*
  5. maximum number of fencepoints
  6. */
  7. uint8_t AC_PolyFence_loader::max_points() const
  8. {
  9. return MIN(255U, fence_storage.size() / sizeof(Vector2l));
  10. }
  11. // create buffer to hold copy of eeprom points in RAM
  12. // returns nullptr if not enough memory can be allocated
  13. void* AC_PolyFence_loader::create_point_array(uint8_t element_size)
  14. {
  15. uint32_t array_size = max_points() * element_size;
  16. if (hal.util->available_memory() < 100U + array_size) {
  17. // too risky to enable as we could run out of stack
  18. return nullptr;
  19. }
  20. return calloc(1, array_size);
  21. }
  22. // load boundary point from eeprom, returns true on successful load
  23. bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point)
  24. {
  25. // sanity check index
  26. if (i >= max_points()) {
  27. return false;
  28. }
  29. // read fence point
  30. point.x = fence_storage.read_uint32(i * sizeof(Vector2l));
  31. point.y = fence_storage.read_uint32(i * sizeof(Vector2l) + sizeof(uint32_t));
  32. return true;
  33. }
  34. // save a fence point to eeprom, returns true on successful save
  35. bool AC_PolyFence_loader::save_point_to_eeprom(uint16_t i, const Vector2l& point)
  36. {
  37. // sanity check index
  38. if (i >= max_points()) {
  39. return false;
  40. }
  41. // write point to eeprom
  42. fence_storage.write_uint32(i * sizeof(Vector2l), point.x);
  43. fence_storage.write_uint32(i * sizeof(Vector2l)+sizeof(uint32_t), point.y);
  44. return true;
  45. }
  46. // validate array of boundary points (expressed as either floats or long ints)
  47. // returns true if boundary is valid
  48. template <typename T>
  49. bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2<T>* points) const
  50. {
  51. // exit immediate if no points
  52. if (points == nullptr) {
  53. return false;
  54. }
  55. // start from 2nd point as boundary contains return point (as first point)
  56. uint8_t start_num = 1;
  57. // a boundary requires at least 4 point (a triangle and last point equals first)
  58. if (num_points < start_num + 4) {
  59. return false;
  60. }
  61. // point 1 and last point must be the same. Note: 0th point is reserved as the return point
  62. if (!Polygon_complete(&points[start_num], num_points-start_num)) {
  63. return false;
  64. }
  65. // check return point is within the fence
  66. if (Polygon_outside(points[0], &points[1], num_points-start_num)) {
  67. return false;
  68. }
  69. return true;
  70. }
  71. // check if a location (expressed as either floats or long ints) is within the boundary
  72. // returns true if location is outside the boundary
  73. template <typename T>
  74. bool AC_PolyFence_loader::boundary_breached(const Vector2<T>& location, uint16_t num_points, const Vector2<T>* points) const
  75. {
  76. // exit immediate if no points
  77. if (points == nullptr) {
  78. return false;
  79. }
  80. // start from 2nd point as boundary contains return point (as first point)
  81. uint8_t start_num = 1;
  82. // check location is within the fence
  83. return Polygon_outside(location, &points[start_num], num_points-start_num);
  84. }
  85. // declare type specific methods
  86. template bool AC_PolyFence_loader::boundary_valid<int32_t>(uint16_t num_points, const Vector2l* points) const;
  87. template bool AC_PolyFence_loader::boundary_valid<float>(uint16_t num_points, const Vector2f* points) const;
  88. template bool AC_PolyFence_loader::boundary_breached<int32_t>(const Vector2l& location, uint16_t num_points,
  89. const Vector2l* points) const;
  90. template bool AC_PolyFence_loader::boundary_breached<float>(const Vector2f& location, uint16_t num_points,
  91. const Vector2f* points) const;