aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/commander.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-05-09 15:58:23 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-05-09 15:58:23 +0200
commit614bbb15109236c353c02b1d2c2494bc442a699f (patch)
treee661f535b281c8131c4925a9023254e5ae1d8a2d /src/modules/commander/commander.c
parent3152dae3dca9f6104e685fc27da0aba7c09ac3ca (diff)
parent5b60991c63b0c6b87632369fde73236263670448 (diff)
downloadpx4-firmware-614bbb15109236c353c02b1d2c2494bc442a699f.tar.gz
px4-firmware-614bbb15109236c353c02b1d2c2494bc442a699f.tar.bz2
px4-firmware-614bbb15109236c353c02b1d2c2494bc442a699f.zip
Merged ETS airspeed driver
Diffstat (limited to 'src/modules/commander/commander.c')
-rw-r--r--src/modules/commander/commander.c36
1 files changed, 18 insertions, 18 deletions
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index 0f18d6cef..01ab9e3d9 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -676,22 +676,22 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
const int calibration_count = 2500;
- int sub_differential_pressure = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s differential_pressure;
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
int calibration_counter = 0;
- float airspeed_offset = 0.0f;
+ float diff_pres_offset = 0.0f;
while (calibration_counter < calibration_count) {
/* wait blocking for new data */
- struct pollfd fds[1] = { { .fd = sub_differential_pressure, .events = POLLIN } };
+ struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } };
int poll_ret = poll(fds, 1, 1000);
if (poll_ret) {
- orb_copy(ORB_ID(differential_pressure), sub_differential_pressure, &differential_pressure);
- airspeed_offset += differential_pressure.voltage;
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ diff_pres_offset += diff_pres.differential_pressure_pa;
calibration_counter++;
} else if (poll_ret == 0) {
@@ -701,11 +701,11 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
}
}
- airspeed_offset = airspeed_offset / calibration_count;
+ diff_pres_offset = diff_pres_offset / calibration_count;
- if (isfinite(airspeed_offset)) {
+ if (isfinite(diff_pres_offset)) {
- if (param_set(param_find("SENS_VAIR_OFF"), &(airspeed_offset))) {
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
mavlink_log_critical(mavlink_fd, "Setting offs failed!");
}
@@ -735,7 +735,7 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status)
status->flag_preflight_airspeed_calibration = false;
state_machine_publish(status_pub, status, mavlink_fd);
- close(sub_differential_pressure);
+ close(diff_pres_sub);
}
@@ -1356,10 +1356,10 @@ int commander_thread_main(int argc, char *argv[])
struct sensor_combined_s sensors;
memset(&sensors, 0, sizeof(sensors));
- int differential_pressure_sub = orb_subscribe(ORB_ID(differential_pressure));
- struct differential_pressure_s differential_pressure;
- memset(&differential_pressure, 0, sizeof(differential_pressure));
- uint64_t last_differential_pressure_time = 0;
+ int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
+ struct differential_pressure_s diff_pres;
+ memset(&diff_pres, 0, sizeof(diff_pres));
+ uint64_t last_diff_pres_time = 0;
/* Subscribe to command topic */
int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
@@ -1414,11 +1414,11 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
}
- orb_check(differential_pressure_sub, &new_data);
+ orb_check(diff_pres_sub, &new_data);
if (new_data) {
- orb_copy(ORB_ID(differential_pressure), differential_pressure_sub, &differential_pressure);
- last_differential_pressure_time = differential_pressure.timestamp;
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+ last_diff_pres_time = diff_pres.timestamp;
}
orb_check(cmd_sub, &new_data);
@@ -1633,7 +1633,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* Check for valid airspeed/differential pressure measurements */
- if (hrt_absolute_time() - last_differential_pressure_time < 2000000) {
+ if (hrt_absolute_time() - last_diff_pres_time < 2000000) {
current_status.flag_airspeed_valid = true;
} else {