2014-07-20 20:39:12 -03:00
|
|
|
/*
|
|
|
|
* RangeFinder test code
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_RangeFinder.h>
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <Filter.h>
|
|
|
|
#include <AP_Progmem.h>
|
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <AP_Param.h>
|
|
|
|
#include <GCS_MAVLink.h>
|
|
|
|
#include <AP_HAL_Empty.h>
|
|
|
|
#include <AP_HAL_AVR.h>
|
2015-05-04 03:17:16 -03:00
|
|
|
#include <AP_HAL_SITL.h>
|
2014-07-20 20:39:12 -03:00
|
|
|
#include <AP_HAL_PX4.h>
|
|
|
|
#include <AP_HAL_Linux.h>
|
|
|
|
#include <DataFlash.h>
|
|
|
|
#include <AP_GPS.h>
|
|
|
|
#include <AP_InertialSensor.h>
|
|
|
|
#include <AP_ADC.h>
|
|
|
|
#include <AP_Baro.h>
|
|
|
|
#include <AP_AHRS.h>
|
|
|
|
#include <AP_Compass.h>
|
|
|
|
#include <AP_Declination.h>
|
|
|
|
#include <AP_Airspeed.h>
|
|
|
|
#include <AP_Vehicle.h>
|
|
|
|
#include <AP_NavEKF.h>
|
|
|
|
#include <AP_ADC_AnalogSource.h>
|
|
|
|
#include <AP_Notify.h>
|
|
|
|
#include <AP_Mission.h>
|
2014-08-13 08:48:04 -03:00
|
|
|
#include <StorageManager.h>
|
2014-07-25 04:55:11 -03:00
|
|
|
#include <AP_Terrain.h>
|
2014-07-20 20:39:12 -03:00
|
|
|
#include <AP_Scheduler.h>
|
2015-01-28 04:12:49 -04:00
|
|
|
#include <AP_BattMonitor.h>
|
2015-03-14 23:50:59 -03:00
|
|
|
#include <AP_Rally.h>
|
2014-07-20 20:39:12 -03:00
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
|
|
|
|
|
|
|
static RangeFinder sonar;
|
|
|
|
|
|
|
|
void setup()
|
|
|
|
{
|
|
|
|
// print welcome message
|
|
|
|
hal.console->println("Range Finder library test");
|
|
|
|
|
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);
|
|
|
|
AP_Param::set_object_value(&sonar, sonar.var_info, "_PIN", -1);
|
|
|
|
AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0);
|
2014-07-20 20:39:12 -03:00
|
|
|
|
|
|
|
// initialise sensor, delaying to make debug easier
|
|
|
|
hal.scheduler->delay(2000);
|
|
|
|
sonar.init();
|
2014-07-24 12:03:18 -03:00
|
|
|
hal.console->printf_P(PSTR("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
|
|
|
|
2015-04-17 03:36:17 -03:00
|
|
|
hal.console->printf_P(PSTR("Primary: status %d distance_cm %d \n"), (int)sonar.status(), sonar.distance_cm());
|
|
|
|
hal.console->printf_P(PSTR("All: device_0 type %d status %d distance_cm %d, device_1 type %d status %d distance_cm %d\n"),
|
|
|
|
(int)sonar._type[0], (int)sonar.status(0), sonar.distance_cm(0), (int)sonar._type[1], (int)sonar.status(1), sonar.distance_cm(1));
|
2014-07-24 12:03:18 -03:00
|
|
|
|
2014-07-20 20:39:12 -03:00
|
|
|
}
|
|
|
|
AP_HAL_MAIN();
|