APM:Libraries
RFIND_test.cpp
Go to the documentation of this file.
1 /*
2  * RangeFinder test code
3  */
4 
5 #include <AP_HAL/AP_HAL.h>
7 
8 void setup();
9 void loop();
10 
12 
15 
16 void setup()
17 {
18  // print welcome message
19  hal.console->printf("Range Finder library test\n");
20 
21  // setup for analog pin 13
24  AP_Param::set_object_value(&sonar, sonar.var_info, "_SCALING", 1.0f);
25 
26  // initialise sensor, delaying to make debug easier
27  hal.scheduler->delay(2000);
28  sonar.init();
29  hal.console->printf("RangeFinder: %d devices detected\n", sonar.num_sensors());
30 }
31 
32 void loop()
33 {
34  // Delay between reads
35  hal.scheduler->delay(100);
36  sonar.update();
37 
38  bool had_data = false;
39  for (uint8_t i=0; i<sonar.num_sensors(); i++) {
41  if (sensor == nullptr) {
42  continue;
43  }
44  if (!sensor->has_data()) {
45  continue;
46  }
47  hal.console->printf("All: device_%u type %d status %d distance_cm %d\n",
48  i,
49  (int)sensor->type(),
50  (int)sensor->status(),
51  sensor->distance_cm());
52  had_data = true;
53  }
54  if (!had_data) {
55  hal.console->printf("All: no data on any sensor\n");
56  }
57 
58 }
59 AP_HAL_MAIN();
AP_RangeFinder_Backend * get_backend(uint8_t id) const
RangeFinder::RangeFinder_Type type() const
void update(void)
uint16_t distance_cm() const
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void loop()
Definition: RFIND_test.cpp:32
void setup()
Definition: RFIND_test.cpp:16
static const struct AP_Param::GroupInfo var_info[]
Definition: RangeFinder.h:114
uint8_t num_sensors(void) const
Definition: RangeFinder.h:117
virtual void delay(uint16_t ms)=0
static AP_SerialManager serial_manager
Definition: RFIND_test.cpp:13
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
AP_HAL_MAIN()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RFIND_test.cpp:11
const HAL & get_HAL()
static RangeFinder sonar
Definition: RFIND_test.cpp:14
RangeFinder::RangeFinder_Status status() const
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
Definition: AP_Param.cpp:1231
void init(void)
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114