RFIND_test.cpp 1.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. /*
  2. * RangeFinder test code
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_RangeFinder/RangeFinder_Backend.h>
  6. void setup();
  7. void loop();
  8. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  9. static AP_SerialManager serial_manager;
  10. static RangeFinder sonar;
  11. void setup()
  12. {
  13. // print welcome message
  14. hal.console->printf("Range Finder library test\n");
  15. // setup for analog pin 13
  16. AP_Param::set_object_value(&sonar, sonar.var_info, "_TYPE", RangeFinder::RangeFinder_TYPE_PLI2C);
  17. AP_Param::set_object_value(&sonar, sonar.var_info, "_PIN", -1.0f);
  18. AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0f);
  19. // initialise sensor, delaying to make debug easier
  20. hal.scheduler->delay(2000);
  21. sonar.init(ROTATION_PITCH_270);
  22. hal.console->printf("RangeFinder: %d devices detected\n", sonar.num_sensors());
  23. }
  24. void loop()
  25. {
  26. // Delay between reads
  27. hal.scheduler->delay(100);
  28. sonar.update();
  29. bool had_data = false;
  30. for (uint8_t i=0; i<sonar.num_sensors(); i++) {
  31. AP_RangeFinder_Backend *sensor = sonar.get_backend(i);
  32. if (sensor == nullptr) {
  33. continue;
  34. }
  35. if (!sensor->has_data()) {
  36. continue;
  37. }
  38. hal.console->printf("All: device_%u type %d status %d distance_cm %d\n",
  39. i,
  40. (int)sensor->type(),
  41. (int)sensor->status(),
  42. sensor->distance_cm());
  43. had_data = true;
  44. }
  45. if (!had_data) {
  46. hal.console->printf("All: no data on any sensor\n");
  47. }
  48. }
  49. AP_HAL_MAIN();