Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

HIL and fixed wing fixes - gives perfect results in simulation #447

Merged
merged 21 commits into from
Oct 10, 2013
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
f7c3ed3
px4io: split io_handle_battery() out from io_handle_status()
Sep 12, 2013
f12794d
uORB: added new servorail_status object
Sep 12, 2013
e9e46f9
px4io: added monitoring of vservo and vrssi
Sep 12, 2013
0b7294a
added error_count field to sensor report structures
Sep 12, 2013
7257642
perf: added perf_event_count() method
Sep 12, 2013
c9b8a01
Merge branch 'master' of github.com:PX4/Firmware into status_monitoring
LorenzMeier Sep 12, 2013
4893509
drivers: report error_count in drivers where possible
Sep 12, 2013
6a784b7
Merge branch 'master' of github.com:PX4/Firmware into status_monitoring
LorenzMeier Sep 13, 2013
90c4664
Merged status changes
LorenzMeier Oct 6, 2013
d1871bd
State machine fixes for HIL
LorenzMeier Oct 6, 2013
81e9c06
Robustified flight close to waypoints
LorenzMeier Oct 6, 2013
69fda8a
Added useful default gains
LorenzMeier Oct 8, 2013
5bc7d7c
Fixed turn radius return value
LorenzMeier Oct 8, 2013
d59cdf6
Added support for dynamic turn radii
LorenzMeier Oct 8, 2013
a3bdf53
Dynamic integral resets for straight and circle mode, announcing turn…
LorenzMeier Oct 8, 2013
d63ad0f
Added debug output printing capabilities for IOv2
LorenzMeier Oct 9, 2013
ed00567
Extended file test for alignment
LorenzMeier Oct 9, 2013
b8ccf67
Merge branch 'sdtest' of github.com:PX4/Firmware into hil_usb_only
LorenzMeier Oct 9, 2013
1ca718b
Slight fix to test, but still fails validating written data after non…
LorenzMeier Oct 9, 2013
d8396ca
Merge branch 'sdtest' into hil_usb_only
LorenzMeier Oct 9, 2013
13b07ef
added hw test, added better io debugging
LorenzMeier Oct 9, 2013
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions ROMFS/px4fmu_common/init.d/1000_rc_fw.hil
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ then
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16

param set SYS_AUTOCONFIG 0
param save
Expand Down
22 changes: 21 additions & 1 deletion ROMFS/px4fmu_common/init.d/100_mpx_easystar
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,27 @@ echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
# TODO
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1.1
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
param set FW_THR_MAX 1
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16

param set SYS_AUTOCONFIG 0
param save
Expand Down
22 changes: 21 additions & 1 deletion ROMFS/px4fmu_common/init.d/101_hk_bixler
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,27 @@ echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
# TODO
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1.1
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
param set FW_THR_MAX 1
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 16

param set SYS_AUTOCONFIG 0
param save
Expand Down
22 changes: 21 additions & 1 deletion ROMFS/px4fmu_common/init.d/31_io_phantom
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,27 @@ echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
# TODO
param set FW_P_D 0
param set FW_P_I 0
param set FW_P_IMAX 15
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_P 60
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1.1
param set FW_R_D 0
param set FW_R_I 5
param set FW_R_IMAX 20
param set FW_R_P 100
param set FW_R_RMAX 100
param set FW_THR_CRUISE 0.65
param set FW_THR_MAX 1
param set FW_THR_MIN 0
param set FW_T_SINK_MAX 5.0
param set FW_T_SINK_MIN 4.0
param set FW_Y_ROLLFF 1.1
param set FW_L1_PERIOD 17

param set SYS_AUTOCONFIG 0
param save
Expand Down
9 changes: 9 additions & 0 deletions ROMFS/px4fmu_common/init.d/cmp_test
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#!nsh

cp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
if cmp /etc/extras/px4io-v2_default.bin /fs/microsd/px4io.loaded
then
echo "CMP returned true"
else
echo "CMP returned false"
fi
3 changes: 3 additions & 0 deletions makefiles/config_px4fmu-v2_default.mk
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,9 @@ MODULES += lib/geo
# https://pixhawk.ethz.ch/px4/dev/debug_values
#MODULES += examples/px4_mavlink_debug

# Hardware test
MODULES += examples/hwtest

#
# Transitional support - add commands from the NuttX export archive.
#
Expand Down
1 change: 1 addition & 0 deletions src/drivers/bma180/bma180.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -690,6 +690,7 @@ BMA180::measure()
* measurement flow without using the external interrupt.
*/
report.timestamp = hrt_absolute_time();
report.error_count = 0;
/*
* y of board is x of sensor and x of board is -y of sensor
* perform only the axis assignment here.
Expand Down
1 change: 1 addition & 0 deletions src/drivers/drv_accel.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
*/
struct accel_report {
uint64_t timestamp;
uint64_t error_count;
float x; /**< acceleration in the NED X board axis in m/s^2 */
float y; /**< acceleration in the NED Y board axis in m/s^2 */
float z; /**< acceleration in the NED Z board axis in m/s^2 */
Expand Down
1 change: 1 addition & 0 deletions src/drivers/drv_baro.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ struct baro_report {
float altitude;
float temperature;
uint64_t timestamp;
uint64_t error_count;
};

/*
Expand Down
1 change: 1 addition & 0 deletions src/drivers/drv_gyro.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
*/
struct gyro_report {
uint64_t timestamp;
uint64_t error_count;
float x; /**< angular velocity in the NED X board axis in rad/s */
float y; /**< angular velocity in the NED Y board axis in rad/s */
float z; /**< angular velocity in the NED Z board axis in rad/s */
Expand Down
1 change: 1 addition & 0 deletions src/drivers/drv_mag.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
*/
struct mag_report {
uint64_t timestamp;
uint64_t error_count;
float x;
float y;
float z;
Expand Down
1 change: 1 addition & 0 deletions src/drivers/drv_range_finder.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
*/
struct range_finder_report {
uint64_t timestamp;
uint64_t error_count;
float distance; /** in meters */
uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
};
Expand Down
21 changes: 11 additions & 10 deletions src/drivers/ets_airspeed/ets_airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,35 +153,36 @@ ETSAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 2);

if (ret < 0) {
log("error reading from sensor: %d", ret);
perf_count(_comms_errors);
return ret;
}

uint16_t diff_pres_pa = val[1] << 8 | val[0];
if (diff_pres_pa == 0) {
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
// caller could end up using this value as part of an
// average
log("zero value from sensor");
return -1;
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
// caller could end up using this value as part of an
// average
perf_count(_comms_errors);
log("zero value from sensor");
return -1;
}

if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;

} else {
diff_pres_pa -= _diff_pres_offset;
}

// Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_pres_pa;
_max_differential_pressure_pa = diff_pres_pa;
}

// XXX we may want to smooth out the readings to remove noise.
differential_pressure_s report;
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.differential_pressure_pa = diff_pres_pa;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
Expand Down Expand Up @@ -209,7 +210,7 @@ ETSAirspeed::cycle()

/* perform collection */
if (OK != collect()) {
log("collection error");
perf_count(_comms_errors);
/* restart the measurement state machine */
start();
return;
Expand Down
1 change: 1 addition & 0 deletions src/drivers/hmc5883/hmc5883.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -791,6 +791,7 @@ HMC5883::collect()

/* this should be fairly close to the end of the measurement, so the best approximation of the time */
new_report.timestamp = hrt_absolute_time();
new_report.error_count = perf_event_count(_comms_errors);

/*
* @note We could read the status register here, which could tell us that
Expand Down
1 change: 1 addition & 0 deletions src/drivers/l3gd20/l3gd20.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -771,6 +771,7 @@ L3GD20::measure()
* 74 from all measurements centers them around zero.
*/
report.timestamp = hrt_absolute_time();
report.error_count = 0; // not recorded

switch (_orientation) {

Expand Down
1 change: 1 addition & 0 deletions src/drivers/lsm303d/lsm303d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1248,6 +1248,7 @@ LSM303D::measure()


accel_report.timestamp = hrt_absolute_time();
accel_report.error_count = 0; // not reported

accel_report.x_raw = raw_accel_report.x;
accel_report.y_raw = raw_accel_report.y;
Expand Down
1 change: 1 addition & 0 deletions src/drivers/mb12xx/mb12xx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -490,6 +490,7 @@ MB12XX::collect()

/* this should be fairly close to the end of the measurement, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.distance = si_units;
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;

Expand Down
4 changes: 1 addition & 3 deletions src/drivers/meas_airspeed/meas_airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,6 @@ MEASAirspeed::measure()

if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
return ret;
}

Expand All @@ -161,7 +160,6 @@ MEASAirspeed::collect()
ret = transfer(nullptr, 0, &val[0], 4);

if (ret < 0) {
log("error reading from sensor: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
Expand Down Expand Up @@ -207,6 +205,7 @@ MEASAirspeed::collect()
}

report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature;
report.differential_pressure_pa = diff_press_pa;
report.voltage = 0;
Expand Down Expand Up @@ -235,7 +234,6 @@ MEASAirspeed::cycle()

/* perform collection */
if (OK != collect()) {
log("collection error");
/* restart the measurement state machine */
start();
return;
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/mpu6000/mpu6000.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1186,7 +1186,7 @@ MPU6000::measure()
* Adjust and scale results to m/s^2.
*/
grb.timestamp = arb.timestamp = hrt_absolute_time();

grb.error_count = arb.error_count = 0; // not reported

/*
* 1) Scale raw value to SI units using scaling from datasheet.
Expand Down
1 change: 1 addition & 0 deletions src/drivers/ms5611/ms5611.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -573,6 +573,7 @@ MS5611::collect()
struct baro_report report;
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);

/* read the most recent measurement - read offset/size are hardcoded in the interface */
ret = _interface->read(0, (void *)&raw, 0);
Expand Down
Loading