2014-07-20 20:39:12 -03:00
|
|
|
/*
|
|
|
|
* RangeFinder test code
|
|
|
|
*/
|
2015-10-20 10:51:24 -03:00
|
|
|
|
2015-08-11 03:28:45 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2017-08-08 02:54:09 -03:00
|
|
|
#include <AP_RangeFinder/RangeFinder_Backend.h>
|
2014-07-20 20:39:12 -03:00
|
|
|
|
2017-04-13 08:33:02 -03:00
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2014-07-20 20:39:12 -03:00
|
|
|
|
2017-12-12 21:06:13 -04:00
|
|
|
static AP_SerialManager serial_manager;
|
2019-07-09 03:14:52 -03:00
|
|
|
static RangeFinder sonar;
|
2014-07-20 20:39:12 -03:00
|
|
|
|
|
|
|
void setup()
|
|
|
|
{
|
|
|
|
// print welcome message
|
2017-01-21 01:01:05 -04:00
|
|
|
hal.console->printf("Range Finder library test\n");
|
2014-07-20 20:39:12 -03:00
|
|
|
|
2014-07-21 11:05:35 -03:00
|
|
|
// setup for analog pin 13
|
2015-03-14 23:50:59 -03:00
|
|
|
AP_Param::set_object_value(&sonar, sonar.var_info, "_TYPE", RangeFinder::RangeFinder_TYPE_PLI2C);
|
2017-04-13 08:33:02 -03:00
|
|
|
AP_Param::set_object_value(&sonar, sonar.var_info, "_PIN", -1.0f);
|
|
|
|
AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0f);
|
2014-07-20 20:39:12 -03:00
|
|
|
|
|
|
|
// initialise sensor, delaying to make debug easier
|
|
|
|
hal.scheduler->delay(2000);
|
2019-04-05 06:13:42 -03:00
|
|
|
sonar.init(ROTATION_PITCH_270);
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("RangeFinder: %d devices detected\n", sonar.num_sensors());
|
2014-07-20 20:39:12 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop()
|
|
|
|
{
|
|
|
|
// Delay between reads
|
|
|
|
hal.scheduler->delay(100);
|
2014-07-24 12:03:18 -03:00
|
|
|
sonar.update();
|
2014-07-21 11:05:35 -03:00
|
|
|
|
2017-08-08 02:54:09 -03:00
|
|
|
bool had_data = false;
|
|
|
|
for (uint8_t i=0; i<sonar.num_sensors(); i++) {
|
|
|
|
AP_RangeFinder_Backend *sensor = sonar.get_backend(i);
|
|
|
|
if (sensor == nullptr) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (!sensor->has_data()) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
hal.console->printf("All: device_%u type %d status %d distance_cm %d\n",
|
|
|
|
i,
|
|
|
|
(int)sensor->type(),
|
|
|
|
(int)sensor->status(),
|
|
|
|
sensor->distance_cm());
|
|
|
|
had_data = true;
|
|
|
|
}
|
|
|
|
if (!had_data) {
|
|
|
|
hal.console->printf("All: no data on any sensor\n");
|
|
|
|
}
|
2014-07-24 12:03:18 -03:00
|
|
|
|
2014-07-20 20:39:12 -03:00
|
|
|
}
|
|
|
|
AP_HAL_MAIN();
|