mirror of https://github.com/ArduPilot/ardupilot
Examples: fix examples for px4
The change to use AP_BoardConfig messed up the examples. Here are some updated but there are plenty more to do.
This commit is contained in:
parent
467da77c77
commit
0d113b265c
|
@ -7,6 +7,7 @@
|
|||
#include <AP_ADC/AP_ADC.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -29,6 +30,8 @@ AP_AHRS_DCM ahrs(ins, baro, gps);
|
|||
|
||||
void setup(void)
|
||||
{
|
||||
AP_BoardConfig{}.init();
|
||||
|
||||
ins.init(100);
|
||||
ahrs.init();
|
||||
serial_manager.init();
|
||||
|
|
|
@ -26,3 +26,4 @@ LIBRARIES += Filter
|
|||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += RC_Channel
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <AP_ADC/AP_ADC.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -29,13 +30,28 @@ float temperature;
|
|||
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
namespace {
|
||||
// try to set the object value but provide diagnostic if it failed
|
||||
void set_object_value(const void *object_pointer,
|
||||
const struct AP_Param::GroupInfo *group_info,
|
||||
const char *name, float value)
|
||||
{
|
||||
if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {
|
||||
hal.console->printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
|
||||
group_info->name, name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
hal.console->println("ArduPilot Airspeed library test");
|
||||
|
||||
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_PIN", 65);
|
||||
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_ENABLE", 1);
|
||||
AP_Param::set_object_value(&airspeed, airspeed.var_info, "_USE", 1);
|
||||
set_object_value(&airspeed, airspeed.var_info, "PIN", 65);
|
||||
set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1);
|
||||
set_object_value(&airspeed, airspeed.var_info, "USE", 1);
|
||||
|
||||
AP_BoardConfig{}.init();
|
||||
|
||||
airspeed.init();
|
||||
airspeed.calibrate(false);
|
||||
|
@ -44,12 +60,13 @@ void setup()
|
|||
void loop(void)
|
||||
{
|
||||
static uint32_t timer;
|
||||
if((AP_HAL::millis() - timer) > 100) {
|
||||
if ((AP_HAL::millis() - timer) > 100) {
|
||||
timer = AP_HAL::millis();
|
||||
airspeed.read();
|
||||
airspeed.get_temperature(temperature);
|
||||
|
||||
hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n", airspeed.get_airspeed(), temperature, airspeed.healthy());
|
||||
hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",
|
||||
airspeed.get_airspeed(), temperature, airspeed.healthy());
|
||||
}
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
|
|
|
@ -23,3 +23,4 @@ LIBRARIES += DataFlash
|
|||
LIBRARIES += Filter
|
||||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -16,6 +17,8 @@ void setup()
|
|||
{
|
||||
hal.console->println("Barometer library test");
|
||||
|
||||
AP_BoardConfig{}.init();
|
||||
|
||||
hal.scheduler->delay(1000);
|
||||
|
||||
barometer.init();
|
||||
|
|
|
@ -24,3 +24,4 @@ LIBRARIES += DataFlash
|
|||
LIBRARIES += Filter
|
||||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
|
||||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -12,9 +13,12 @@ static Compass compass;
|
|||
|
||||
uint32_t timer;
|
||||
|
||||
void setup() {
|
||||
static void setup()
|
||||
{
|
||||
hal.console->println("Compass library test");
|
||||
|
||||
AP_BoardConfig{}.init(); // initialise the board drivers
|
||||
|
||||
if (!compass.init()) {
|
||||
AP_HAL::panic("compass initialisation failed!");
|
||||
}
|
||||
|
@ -29,7 +33,7 @@ void setup() {
|
|||
timer = AP_HAL::micros();
|
||||
}
|
||||
|
||||
void loop()
|
||||
static void loop()
|
||||
{
|
||||
static const uint8_t compass_count = compass.get_count();
|
||||
static float min[COMPASS_MAX_INSTANCES][3];
|
||||
|
|
|
@ -1,25 +1,9 @@
|
|||
LIBRARIES += AP_ADC
|
||||
LIBRARIES += AP_AHRS
|
||||
LIBRARIES += AP_Airspeed
|
||||
LIBRARIES += AP_Baro
|
||||
LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_Common
|
||||
LIBRARIES += AP_Compass
|
||||
LIBRARIES += AP_Declination
|
||||
LIBRARIES += AP_GPS
|
||||
LIBRARIES += AP_InertialSensor
|
||||
LIBRARIES += AP_AccelCal
|
||||
LIBRARIES += AP_Math
|
||||
LIBRARIES += AP_Mission
|
||||
LIBRARIES += AP_NavEKF
|
||||
LIBRARIES += AP_Notify
|
||||
LIBRARIES += AP_Param
|
||||
LIBRARIES += AP_Rally
|
||||
LIBRARIES += AP_RangeFinder
|
||||
LIBRARIES += AP_Scheduler
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += AP_Vehicle
|
||||
LIBRARIES += DataFlash
|
||||
LIBRARIES += Filter
|
||||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -51,6 +52,8 @@ void setup()
|
|||
{
|
||||
hal.console->println("GPS AUTO library test");
|
||||
|
||||
AP_BoardConfig{}.init();
|
||||
|
||||
// Initialise the leds
|
||||
board_led.init();
|
||||
|
||||
|
|
|
@ -24,3 +24,4 @@ LIBRARIES += DataFlash
|
|||
LIBRARIES += Filter
|
||||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
|
@ -1168,20 +1168,24 @@ void AP_Param::setup_object_defaults(const void *object_pointer, const struct Gr
|
|||
|
||||
// set a value directly in an object. This should only be used by
|
||||
// example code, not by mainline vehicle code
|
||||
void AP_Param::set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
bool AP_Param::set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
const char *name, float value)
|
||||
{
|
||||
ptrdiff_t base = (ptrdiff_t)object_pointer;
|
||||
uint8_t type;
|
||||
bool found = false;
|
||||
for (uint8_t i=0;
|
||||
(type=group_info[i].type) != AP_PARAM_NONE;
|
||||
i++) {
|
||||
if (strcmp(name, group_info[i].name) == 0 && type <= AP_PARAM_FLOAT) {
|
||||
void *ptr = (void *)(base + group_info[i].offset);
|
||||
set_value((enum ap_var_type)type, ptr, value);
|
||||
// return true here ?
|
||||
found = true;
|
||||
}
|
||||
}
|
||||
return found;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -278,10 +278,11 @@ public:
|
|||
// load default values for scalars in a group
|
||||
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);
|
||||
|
||||
// set a value directly in an object. This should only be used by
|
||||
// example code, not by mainline vehicle code
|
||||
static void set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
// set a value directly in an object.
|
||||
// return true if the name was found and set, else false.
|
||||
// This should only be used by example code, not by mainline vehicle code
|
||||
static bool set_object_value(const void *object_pointer,
|
||||
const struct GroupInfo *group_info,
|
||||
const char *name, float value);
|
||||
|
||||
// load default values for all scalars in the main sketch. This
|
||||
|
|
|
@ -7,6 +7,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
|
@ -46,6 +47,9 @@ const AP_Scheduler::Task SchedTest::scheduler_tasks[] = {
|
|||
|
||||
void SchedTest::setup(void)
|
||||
{
|
||||
|
||||
AP_BoardConfig{}.init();
|
||||
|
||||
ins.init(scheduler.get_loop_rate_hz());
|
||||
|
||||
// initialise the scheduler
|
||||
|
|
|
@ -1,27 +1,12 @@
|
|||
LIBRARIES += AP_ADC
|
||||
LIBRARIES += AP_AHRS
|
||||
LIBRARIES += AP_Airspeed
|
||||
LIBRARIES += AP_Baro
|
||||
LIBRARIES += AP_BattMonitor
|
||||
LIBRARIES += AP_Buffer
|
||||
LIBRARIES += AP_Common
|
||||
LIBRARIES += AP_Compass
|
||||
LIBRARIES += AP_Declination
|
||||
LIBRARIES += AP_GPS
|
||||
LIBRARIES += AP_InertialSensor
|
||||
LIBRARIES += AP_AccelCal
|
||||
LIBRARIES += AP_Math
|
||||
LIBRARIES += AP_Mission
|
||||
LIBRARIES += AP_NavEKF
|
||||
LIBRARIES += AP_Notify
|
||||
LIBRARIES += AP_Param
|
||||
LIBRARIES += AP_Rally
|
||||
LIBRARIES += AP_RangeFinder
|
||||
LIBRARIES += AP_Scheduler
|
||||
LIBRARIES += AP_Terrain
|
||||
LIBRARIES += AP_Vehicle
|
||||
LIBRARIES += DataFlash
|
||||
LIBRARIES += Filter
|
||||
LIBRARIES += GCS_MAVLink
|
||||
LIBRARIES += StorageManager
|
||||
LIBRARIES += AP_OpticalFlow
|
||||
LIBRARIES += AP_BoardConfig
|
||||
|
|
Loading…
Reference in New Issue