Skip to content

Commit

Permalink
Merge branch 'beta' into stable
Browse files Browse the repository at this point in the history
  • Loading branch information
LorenzMeier committed Aug 23, 2015
2 parents b8517eb + 3ccb35f commit 401d356
Show file tree
Hide file tree
Showing 16 changed files with 150 additions and 86 deletions.
2 changes: 2 additions & 0 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,7 @@ then
if [ $HIL == yes ]
then
set OUTPUT_MODE hil
set GPS no
if ver hwcmp PX4FMU_V1
then
set FMU_MODE serial
Expand Down Expand Up @@ -319,6 +320,7 @@ then
gps start
fi
fi
unset GPS
unset GPS_FAKE

# Needs to be this early for in-air-restarts
Expand Down
8 changes: 4 additions & 4 deletions makefiles/config_px4fmu-v2_default.mk
Original file line number Diff line number Diff line change
Expand Up @@ -140,19 +140,19 @@ MODULES += examples/rover_steering_control
#
#MODULES += examples/math_demo
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/hello_sky
# https://px4.io/dev/px4_simple_app
#MODULES += examples/px4_simple_app

# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/daemon
# https://px4.io/dev/daemon
#MODULES += examples/px4_daemon_app

# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/debug_values
# https://px4.io/dev/debug_values
#MODULES += examples/px4_mavlink_debug

# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
# https://px4.io/dev/example_fixedwing_control
#MODULES += examples/fixedwing_control

# Hardware test
Expand Down
4 changes: 2 additions & 2 deletions msg/tecs_status.msg
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ float32 energyDistributionError
float32 totalEnergyRateError
float32 energyDistributionRateError

float32 throttle_sp
float32 pitch_sp
float32 throttle_integ
float32 pitch_integ

uint8 mode
75 changes: 46 additions & 29 deletions src/drivers/airspeed/airspeed.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
Expand Down Expand Up @@ -32,8 +32,9 @@
****************************************************************************/

/**
* @file ets_airspeed.cpp
* @author Simon Wilks
* @file airspeed.cpp
* @author Simon Wilks <simon@px4.io>
* @author Lorenz Meier <lorenz@px4.io>
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
Expand Down Expand Up @@ -76,7 +77,7 @@

#include <drivers/airspeed/airspeed.h>

Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const char* path) :
Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const char *path) :
I2C("Airspeed", path, bus, address, 100000),
_reports(nullptr),
_buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")),
Expand Down Expand Up @@ -105,12 +106,14 @@ Airspeed::~Airspeed()
/* make sure we are truly inactive */
stop();

if (_class_instance != -1)
if (_class_instance != -1) {
unregister_class_devname(AIRSPEED_BASE_DEVICE_PATH, _class_instance);
}

/* free any existing reports */
if (_reports != nullptr)
if (_reports != nullptr) {
delete _reports;
}

// free perf counters
perf_free(_sample_perf);
Expand All @@ -124,13 +127,16 @@ Airspeed::init()
int ret = ERROR;

/* do I2C init (and probe) first */
if (I2C::init() != OK)
if (I2C::init() != OK) {
goto out;
}

/* allocate basic report buffers */
_reports = new RingBuffer(2, sizeof(differential_pressure_s));
if (_reports == nullptr)

if (_reports == nullptr) {
goto out;
}

/* register alternate interfaces if we have to */
_class_instance = register_class_devname(AIRSPEED_BASE_DEVICE_PATH);
Expand All @@ -146,8 +152,9 @@ Airspeed::init()
/* measurement will have generated a report, publish */
_airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp);

if (_airspeed_pub < 0)
if (_airspeed_pub < 0) {
warnx("uORB started?");
}
}

ret = OK;
Expand All @@ -166,7 +173,7 @@ Airspeed::probe()
_retries = 4;
int ret = measure();

// drop back to 2 retries once initialised
// drop back to 2 retries once initialised
_retries = 2;
return ret;
}
Expand All @@ -179,20 +186,20 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCSPOLLRATE: {
switch (arg) {

/* switching to manual polling */
/* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
stop();
_measure_ticks = 0;
return OK;

/* external signalling (DRDY) not supported */
/* external signalling (DRDY) not supported */
case SENSOR_POLLRATE_EXTERNAL:

/* zero would be bad */
/* zero would be bad */
case 0:
return -EINVAL;

/* set default/max polling rate */
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
Expand All @@ -202,13 +209,14 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks = USEC2TICK(_conversion_interval);

/* if we need to start the poll state machine, do it */
if (want_start)
if (want_start) {
start();
}

return OK;
}

/* adjust to a legal polling interval in Hz */
/* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
Expand All @@ -217,37 +225,43 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
unsigned ticks = USEC2TICK(1000000 / arg);

/* check against maximum rate */
if (ticks < USEC2TICK(_conversion_interval))
if (ticks < USEC2TICK(_conversion_interval)) {
return -EINVAL;
}

/* update interval for next measurement */
_measure_ticks = ticks;

/* if we need to start the poll state machine, do it */
if (want_start)
if (want_start) {
start();
}

return OK;
}
}
}

case SENSORIOCGPOLLRATE:
if (_measure_ticks == 0)
if (_measure_ticks == 0) {
return SENSOR_POLLRATE_MANUAL;
}

return (1000 / _measure_ticks);

case SENSORIOCSQUEUEDEPTH: {
/* lower bound is mandatory, upper bound is a sanity check */
if ((arg < 1) || (arg > 100))
if ((arg < 1) || (arg > 100)) {
return -EINVAL;
}

irqstate_t flags = irqsave();

if (!_reports->resize(arg)) {
irqrestore(flags);
return -ENOMEM;
}

irqrestore(flags);

return OK;
Expand All @@ -261,16 +275,16 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;

case AIRSPEEDIOCSSCALE: {
struct airspeed_scale *s = (struct airspeed_scale*)arg;
_diff_pres_offset = s->offset_pa;
return OK;
struct airspeed_scale *s = (struct airspeed_scale *)arg;
_diff_pres_offset = s->offset_pa;
return OK;
}

case AIRSPEEDIOCGSCALE: {
struct airspeed_scale *s = (struct airspeed_scale*)arg;
s->offset_pa = _diff_pres_offset;
s->scale = 1.0f;
return OK;
struct airspeed_scale *s = (struct airspeed_scale *)arg;
s->offset_pa = _diff_pres_offset;
s->scale = 1.0f;
return OK;
}

default:
Expand All @@ -287,8 +301,9 @@ Airspeed::read(struct file *filp, char *buffer, size_t buflen)
int ret = 0;

/* buffer must be large enough */
if (count < 1)
if (count < 1) {
return -ENOSPC;
}

/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
Expand Down Expand Up @@ -369,6 +384,7 @@ Airspeed::update_status()

if (_subsys_pub > 0) {
orb_publish(ORB_ID(subsystem_info), _subsys_pub, &info);

} else {
_subsys_pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
Expand Down Expand Up @@ -402,6 +418,7 @@ Airspeed::print_info()
void
Airspeed::new_report(const differential_pressure_s &report)
{
if (!_reports->force(&report))
if (!_reports->force(&report)) {
perf_count(_buffer_overflows);
}
}
Loading

0 comments on commit 401d356

Please sign in to comment.