AP_VisualOdom.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153
  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. #include "AP_VisualOdom.h"
  14. #include "AP_VisualOdom_Backend.h"
  15. #include "AP_VisualOdom_MAV.h"
  16. #include <AP_AHRS/AP_AHRS.h>
  17. #include <AP_Logger/AP_Logger.h>
  18. extern const AP_HAL::HAL &hal;
  19. // table of user settable parameters
  20. const AP_Param::GroupInfo AP_VisualOdom::var_info[] = {
  21. // @Param: _TYPE
  22. // @DisplayName: Visual odometry camera connection type
  23. // @Description: Visual odometry camera connection type
  24. // @Values: 0:None,1:MAV
  25. // @User: Advanced
  26. AP_GROUPINFO("_TYPE", 0, AP_VisualOdom, _type, 0),
  27. // @Param: _POS_X
  28. // @DisplayName: Visual odometry camera X position offset
  29. // @Description: X position of the camera in body frame. Positive X is forward of the origin.
  30. // @Units: m
  31. // @User: Advanced
  32. // @Param: _POS_Y
  33. // @DisplayName: Visual odometry camera Y position offset
  34. // @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.
  35. // @Units: m
  36. // @User: Advanced
  37. // @Param: _POS_Z
  38. // @DisplayName: Visual odometry camera Z position offset
  39. // @Description: Z position of the camera in body frame. Positive Z is down from the origin.
  40. // @Units: m
  41. // @User: Advanced
  42. AP_GROUPINFO("_POS", 1, AP_VisualOdom, _pos_offset, 0.0f),
  43. // @Param: _ORIENT
  44. // @DisplayName: Visual odometery camera orientation
  45. // @Description: Visual odometery camera orientation
  46. // @Values: 0:Forward, 2:Right, 4:Back, 6:Left, 24:Up, 25:Down
  47. // @User: Advanced
  48. AP_GROUPINFO("_ORIENT", 2, AP_VisualOdom, _orientation, ROTATION_NONE),
  49. AP_GROUPEND
  50. };
  51. AP_VisualOdom::AP_VisualOdom()
  52. {
  53. AP_Param::setup_object_defaults(this, var_info);
  54. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  55. if (_singleton != nullptr) {
  56. AP_HAL::panic("VisualOdom must be singleton");
  57. }
  58. #endif
  59. _singleton = this;
  60. }
  61. // detect and initialise any sensors
  62. void AP_VisualOdom::init()
  63. {
  64. // create backend
  65. if (_type == AP_VisualOdom_Type_MAV) {
  66. _driver = new AP_VisualOdom_MAV(*this);
  67. }
  68. }
  69. // return true if sensor is enabled
  70. bool AP_VisualOdom::enabled() const
  71. {
  72. return ((_type != AP_VisualOdom_Type_None) && (_driver != nullptr));
  73. }
  74. // update visual odometry sensor
  75. void AP_VisualOdom::update()
  76. {
  77. if (!enabled()) {
  78. return;
  79. }
  80. // check for updates
  81. if (_state.last_processed_sensor_update_ms == _state.last_sensor_update_ms) {
  82. // This reading has already been processed
  83. return;
  84. }
  85. _state.last_processed_sensor_update_ms = _state.last_sensor_update_ms;
  86. const float time_delta_sec = get_time_delta_usec() / 1000000.0f;
  87. AP::ahrs_navekf().writeBodyFrameOdom(get_confidence(),
  88. get_position_delta(),
  89. get_angle_delta(),
  90. time_delta_sec,
  91. get_last_update_ms(),
  92. get_pos_offset());
  93. // log sensor data
  94. AP::logger().Write_VisualOdom(time_delta_sec,
  95. get_angle_delta(),
  96. get_position_delta(),
  97. get_confidence());
  98. }
  99. // return true if sensor is basically healthy (we are receiving data)
  100. bool AP_VisualOdom::healthy() const
  101. {
  102. if (!enabled()) {
  103. return false;
  104. }
  105. // healthy if we have received sensor messages within the past 300ms
  106. return ((AP_HAL::millis() - _state.last_sensor_update_ms) < AP_VISUALODOM_TIMEOUT_MS);
  107. }
  108. // consume VISION_POSITION_DELTA MAVLink message
  109. void AP_VisualOdom::handle_msg(const mavlink_message_t &msg)
  110. {
  111. // exit immediately if not enabled
  112. if (!enabled()) {
  113. return;
  114. }
  115. // call backend
  116. if (_driver != nullptr) {
  117. _driver->handle_msg(msg);
  118. }
  119. }
  120. // singleton instance
  121. AP_VisualOdom *AP_VisualOdom::_singleton;
  122. namespace AP {
  123. AP_VisualOdom *visualodom()
  124. {
  125. return AP_VisualOdom::get_singleton();
  126. }
  127. }