AP_Marvelmind_test.cpp 1.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455
  1. /*
  2. simple test of UART interfaces
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_Beacon/AP_Beacon_Marvelmind.h>
  6. #include <AP_Beacon/AP_Beacon.h>
  7. #include <stdio.h>
  8. void setup();
  9. void loop();
  10. void set_object_value_and_report(const void *object_pointer,
  11. const struct AP_Param::GroupInfo *group_info,
  12. const char *name, float value);
  13. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  14. static AP_SerialManager serial_manager;
  15. AP_Beacon beacon{serial_manager};
  16. // try to set the object value but provide diagnostic if it failed
  17. void set_object_value_and_report(const void *object_pointer,
  18. const struct AP_Param::GroupInfo *group_info,
  19. const char *name, float value)
  20. {
  21. if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {
  22. printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
  23. group_info->name, name);
  24. }
  25. }
  26. void setup(void)
  27. {
  28. set_object_value_and_report(&beacon, beacon.var_info, "_TYPE", 2.0f);
  29. set_object_value_and_report(&serial_manager, serial_manager.var_info, "0_PROTOCOL", 13.0f);
  30. serial_manager.init();
  31. beacon.init();
  32. }
  33. void loop(void)
  34. {
  35. static int count = 0;
  36. beacon.update();
  37. Vector3f pos;
  38. float accuracy = 0.0f;
  39. beacon.get_vehicle_position_ned(pos, accuracy);
  40. if (pos.x > 0.001f) {
  41. printf("%f %f %f\n", static_cast<double>(pos.x), static_cast<double>(pos.y), static_cast<double>(pos.z));
  42. count++;
  43. }
  44. hal.scheduler->delay(1000);
  45. if (count == 3)
  46. exit(0);
  47. }
  48. AP_HAL_MAIN();