RPM_SITL.cpp 1.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748
  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_HAL/AP_HAL.h>
  14. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  15. #include "RPM_SITL.h"
  16. extern const AP_HAL::HAL& hal;
  17. /*
  18. open the sensor in constructor
  19. */
  20. AP_RPM_SITL::AP_RPM_SITL(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
  21. AP_RPM_Backend(_ap_rpm, _instance, _state),
  22. sitl(AP::sitl())
  23. {
  24. instance = _instance;
  25. }
  26. void AP_RPM_SITL::update(void)
  27. {
  28. if (sitl == nullptr) {
  29. return;
  30. }
  31. if (instance == 0) {
  32. state.rate_rpm = sitl->state.rpm1;
  33. } else {
  34. state.rate_rpm = sitl->state.rpm2;
  35. }
  36. state.rate_rpm *= ap_rpm._scaling[state.instance];
  37. state.signal_quality = 0.5f;
  38. state.last_reading_ms = AP_HAL::millis();
  39. }
  40. #endif // CONFIG_HAL_BOARD