APM:Libraries
AP_Marvelmind_test.cpp
Go to the documentation of this file.
1 /*
2  simple test of UART interfaces
3  */
4 
5 #include <AP_HAL/AP_HAL.h>
7 #include <AP_Beacon/AP_Beacon.h>
8 #include <stdio.h>
9 
10 void setup();
11 void loop();
12 void set_object_value_and_report(const void *object_pointer,
13  const struct AP_Param::GroupInfo *group_info,
14  const char *name, float value);
15 
18 AP_Beacon beacon{serial_manager};
19 
20 // try to set the object value but provide diagnostic if it failed
21 void set_object_value_and_report(const void *object_pointer,
22  const struct AP_Param::GroupInfo *group_info,
23  const char *name, float value)
24 {
25  if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {
26  printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
27  group_info->name, name);
28  }
29 }
30 
31 void setup(void)
32 {
34  set_object_value_and_report(&serial_manager, serial_manager.var_info, "0_PROTOCOL", 13.0f);
35  serial_manager.init();
36  beacon.init();
37 }
38 
39 void loop(void)
40 {
41  static int count = 0;
42  beacon.update();
43  Vector3f pos;
44  float accuracy = 0.0f;
45  beacon.get_vehicle_position_ned(pos, accuracy);
46  if (pos.x > 0.001f) {
47  printf("%f %f %f\n", static_cast<double>(pos.x), static_cast<double>(pos.y), static_cast<double>(pos.z));
48  count++;
49  }
50  hal.scheduler->delay(1000);
51  if (count == 3)
52  exit(0);
53 }
54 
55 AP_HAL_MAIN();
int printf(const char *fmt,...)
Definition: stdio.c:113
void loop()
AP_Beacon beacon
void init(void)
Definition: AP_Beacon.cpp:80
void set_object_value_and_report(const void *object_pointer, const struct AP_Param::GroupInfo *group_info, const char *name, float value)
const char * name
Definition: BusTest.cpp:11
virtual void delay(uint16_t ms)=0
bool get_vehicle_position_ned(Vector3f &pos, float &accuracy_estimate) const
Definition: AP_Beacon.cpp:149
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
const char * name
Definition: AP_Param.h:148
const HAL & get_HAL()
AP_HAL_MAIN()
void update(void)
Definition: AP_Beacon.cpp:116
void setup()
float value
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Beacon.h:100
static bool set_object_value(const void *object_pointer, const struct GroupInfo *group_info, const char *name, float value)
Definition: AP_Param.cpp:1231
static const struct AP_Param::GroupInfo var_info[]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static AP_SerialManager serial_manager
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67