mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Baro: added PX4 barometer driver
This commit is contained in:
parent
cf5d102912
commit
2ac6541526
@ -71,5 +71,6 @@ private:
|
||||
#include "AP_Baro_MS5611.h"
|
||||
#include "AP_Baro_BMP085.h"
|
||||
#include "AP_Baro_BMP085_hil.h"
|
||||
#include "AP_Baro_PX4.h"
|
||||
|
||||
#endif // __AP_BARO_H__
|
||||
|
77
libraries/AP_Baro/AP_Baro_PX4.cpp
Normal file
77
libraries/AP_Baro/AP_Baro_PX4.cpp
Normal file
@ -0,0 +1,77 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <AP_Baro.h>
|
||||
#include "AP_Baro_PX4.h"
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <drivers/drv_baro.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/sensor_combined.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
bool AP_Baro_PX4::init(void)
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open(BARO_DEVICE_PATH, 0);
|
||||
if (fd < 0) {
|
||||
hal.scheduler->panic("Unable to open " BARO_DEVICE_PATH);
|
||||
}
|
||||
|
||||
/* set the driver to poll at 150Hz */
|
||||
ioctl(fd, SENSORIOCSPOLLRATE, 150);
|
||||
close(fd);
|
||||
|
||||
_baro_sub = orb_subscribe(ORB_ID(sensor_baro));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Read the sensor
|
||||
uint8_t AP_Baro_PX4::read()
|
||||
{
|
||||
bool baro_updated;
|
||||
orb_check(_baro_sub, &baro_updated);
|
||||
|
||||
if (baro_updated) {
|
||||
struct baro_report baro_report;
|
||||
|
||||
orb_copy(ORB_ID(sensor_baro), _baro_sub, &baro_report);
|
||||
|
||||
_pressure = baro_report.pressure; // Pressure in mbar
|
||||
_temperature = baro_report.temperature; // Temperature in degrees celcius
|
||||
_pressure_samples = 1;
|
||||
_last_update = hal.scheduler->millis();
|
||||
healthy = true;
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
float AP_Baro_PX4::get_pressure() {
|
||||
return _pressure;
|
||||
}
|
||||
|
||||
float AP_Baro_PX4::get_temperature() {
|
||||
return _temperature;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_PX4::get_raw_pressure() {
|
||||
return _pressure;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_PX4::get_raw_temp() {
|
||||
return _temperature;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
26
libraries/AP_Baro/AP_Baro_PX4.h
Normal file
26
libraries/AP_Baro/AP_Baro_PX4.h
Normal file
@ -0,0 +1,26 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_BARO_PX4_H__
|
||||
#define __AP_BARO_PX4_H__
|
||||
|
||||
#include "AP_Baro.h"
|
||||
|
||||
class AP_Baro_PX4 : public AP_Baro
|
||||
{
|
||||
public:
|
||||
bool init();
|
||||
uint8_t read();
|
||||
float get_pressure();
|
||||
float get_temperature();
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
|
||||
private:
|
||||
float _temperature;
|
||||
float _pressure;
|
||||
|
||||
// ORB subscription handle
|
||||
int _baro_sub;
|
||||
};
|
||||
|
||||
#endif // __AP_BARO_PX4_H__
|
@ -0,0 +1,57 @@
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_Buffer.h>
|
||||
#include <Filter.h>
|
||||
#include <AP_Baro.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
||||
AP_Baro_PX4 baro;
|
||||
static uint32_t timer;
|
||||
|
||||
void setup()
|
||||
{
|
||||
hal.console->println("PX4 Barometer library test");
|
||||
|
||||
baro.init();
|
||||
baro.calibrate();
|
||||
|
||||
timer = hal.scheduler->micros();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
hal.scheduler->delay(100);
|
||||
baro.read();
|
||||
|
||||
if (!baro.healthy) {
|
||||
hal.console->println("not healthy");
|
||||
return;
|
||||
}
|
||||
hal.console->print("Pressure:");
|
||||
hal.console->print(baro.get_pressure());
|
||||
hal.console->print(" Temperature:");
|
||||
hal.console->print(baro.get_temperature());
|
||||
hal.console->print(" Altitude:");
|
||||
hal.console->print(baro.get_altitude());
|
||||
hal.console->printf(" climb=%.2f samples=%u",
|
||||
baro.get_climb_rate(),
|
||||
(unsigned)baro.get_pressure_samples());
|
||||
hal.console->println();
|
||||
}
|
||||
|
||||
#else // Non-PX4
|
||||
#warning AP_Baro_PX4_test is PX4 specific
|
||||
void setup () {}
|
||||
void loop () {}
|
||||
#endif
|
||||
|
||||
AP_HAL_MAIN();
|
2
libraries/AP_Baro/examples/AP_Baro_PX4_test/Makefile
Normal file
2
libraries/AP_Baro/examples/AP_Baro_PX4_test/Makefile
Normal file
@ -0,0 +1,2 @@
|
||||
BOARD = mega2560
|
||||
include ../../../../mk/apm.mk
|
Loading…
Reference in New Issue
Block a user