AP_VisualOdom.h 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include <AP_Param/AP_Param.h>
  17. #include <GCS_MAVLink/GCS.h>
  18. class AP_VisualOdom_Backend;
  19. #define AP_VISUALODOM_TIMEOUT_MS 300
  20. class AP_VisualOdom
  21. {
  22. public:
  23. friend class AP_VisualOdom_Backend;
  24. AP_VisualOdom();
  25. // get singleton instance
  26. static AP_VisualOdom *get_singleton() {
  27. return _singleton;
  28. }
  29. // external position backend types (used by _TYPE parameter)
  30. enum AP_VisualOdom_Type {
  31. AP_VisualOdom_Type_None = 0,
  32. AP_VisualOdom_Type_MAV = 1
  33. };
  34. // The VisualOdomState structure is filled in by the backend driver
  35. struct VisualOdomState {
  36. Vector3f angle_delta; // attitude delta (in radians) of most recent update
  37. Vector3f position_delta; // position delta (in meters) of most recent update
  38. uint64_t time_delta_usec; // time delta (in usec) between previous and most recent update
  39. float confidence; // confidence expressed as a value from 0 (no confidence) to 100 (very confident)
  40. uint32_t last_sensor_update_ms; // system time (in milliseconds) of last update from sensor
  41. uint32_t last_processed_sensor_update_ms; // timestamp of last sensor update that was processed
  42. };
  43. // detect and initialise any sensors
  44. void init();
  45. // should be called really, really often. The faster you call
  46. // this the lower the latency of the data fed to the estimator.
  47. void update();
  48. // return true if sensor is enabled
  49. bool enabled() const;
  50. // return true if sensor is basically healthy (we are receiving data)
  51. bool healthy() const;
  52. // return a 3D vector defining the position offset of the camera in meters relative to the body frame origin
  53. const Vector3f &get_pos_offset(void) const { return _pos_offset; }
  54. // consume data from MAVLink messages
  55. void handle_msg(const mavlink_message_t &msg);
  56. static const struct AP_Param::GroupInfo var_info[];
  57. private:
  58. static AP_VisualOdom *_singleton;
  59. // state accessors
  60. const Vector3f &get_angle_delta() const { return _state.angle_delta; }
  61. const Vector3f &get_position_delta() const { return _state.position_delta; }
  62. uint64_t get_time_delta_usec() const { return _state.time_delta_usec; }
  63. float get_confidence() const { return _state.confidence; }
  64. uint32_t get_last_update_ms() const { return _state.last_sensor_update_ms; }
  65. // parameters
  66. AP_Int8 _type;
  67. AP_Vector3f _pos_offset; // position offset of the camera in the body frame
  68. AP_Int8 _orientation; // camera orientation on vehicle frame
  69. // reference to backends
  70. AP_VisualOdom_Backend *_driver;
  71. // state of backend
  72. VisualOdomState _state;
  73. };
  74. namespace AP {
  75. AP_VisualOdom *visualodom();
  76. };