AP_RangeFinder_MAVLink.cpp 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  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_RangeFinder_MAVLink.h"
  14. #include <AP_HAL/AP_HAL.h>
  15. extern const AP_HAL::HAL& hal;
  16. /*
  17. The constructor also initialises the rangefinder. Note that this
  18. constructor is not called until detect() returns true, so we
  19. already know that we should setup the rangefinder
  20. */
  21. AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
  22. AP_RangeFinder_Backend(_state, _params)
  23. {
  24. state.last_reading_ms = AP_HAL::millis();
  25. distance_cm = 0;
  26. }
  27. /*
  28. detect if a MAVLink rangefinder is connected. We'll detect by
  29. checking a parameter.
  30. */
  31. bool AP_RangeFinder_MAVLink::detect()
  32. {
  33. // Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
  34. // there is an attached MAVLink rangefinder
  35. return true;
  36. }
  37. /*
  38. Set the distance based on a MAVLINK message
  39. */
  40. void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
  41. {
  42. mavlink_distance_sensor_t packet;
  43. mavlink_msg_distance_sensor_decode(&msg, &packet);
  44. // only accept distances for downward facing sensors
  45. if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
  46. state.last_reading_ms = AP_HAL::millis();
  47. distance_cm = packet.current_distance;
  48. }
  49. sensor_type = (MAV_DISTANCE_SENSOR)packet.type;
  50. }
  51. /*
  52. update the state of the sensor
  53. */
  54. void AP_RangeFinder_MAVLink::update(void)
  55. {
  56. //Time out on incoming data; if we don't get new
  57. //data in 500ms, dump it
  58. if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) {
  59. set_status(RangeFinder::RangeFinder_NoData);
  60. state.distance_cm = 0;
  61. } else {
  62. state.distance_cm = distance_cm;
  63. update_status();
  64. }
  65. }