aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
commit302233a34f23a57b67d4ebb8ba3e553ad9d8c445 (patch)
tree9fa902073c358151e1ca27430e00919048006d76 /src/modules/commander
parentdfd9601b571057e73668d9b39d584bc4eb9cc305 (diff)
parentf0e28a60ca216ec147b359eef5500f190f192c82 (diff)
downloadpx4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.gz
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.bz2
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.zip
Merge branch 'master' into mpc_local_pos
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/airspeed_calibration.cpp14
-rw-r--r--src/modules/commander/commander.cpp11
2 files changed, 16 insertions, 9 deletions
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 6039d92a7..c8c7a42e7 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 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
@@ -64,9 +64,9 @@ int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "don't move system");
+ mavlink_log_info(mavlink_fd, "ensure airspeed sensor is not registering wind");
- const int calibration_count = 2500;
+ const int calibration_count = 2000;
int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
struct differential_pressure_s diff_pres;
@@ -85,13 +85,15 @@ int do_airspeed_calibration(int mavlink_fd)
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+ } else {
+ mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
close(fd);
}
if (!paramreset_successful) {
- warn("WARNING: failed to set scale / offsets for airspeed sensor");
- mavlink_log_critical(mavlink_fd, "could not reset dpress sensor");
+ warn("FAILED to set scale / offsets for airspeed");
+ mavlink_log_critical(mavlink_fd, "dpress reset failed");
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
return ERROR;
}
@@ -107,7 +109,7 @@ int do_airspeed_calibration(int mavlink_fd)
if (poll_ret) {
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
- diff_pres_offset += diff_pres.differential_pressure_pa;
+ diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
if (calibration_counter % (calibration_count / 20) == 0)
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 531d17145..b90fa4762 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -396,6 +396,11 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
enum VEHICLE_CMD_RESULT result = VEHICLE_CMD_RESULT_UNSUPPORTED;
bool ret = false;
+ /* only handle commands that are meant to be handled by this system and component */
+ if (cmd->target_system != status->system_id || ((cmd->target_component != status->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
+ return false;
+ }
+
/* only handle high-priority commands here */
/* request to set different system mode */
@@ -633,11 +638,11 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
break;
default:
- /* warn about unsupported commands */
+ /* Warn about unsupported commands, this makes sense because only commands
+ * to this component ID (or all) are passed by mavlink. */
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
-
if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, result);
@@ -1047,7 +1052,7 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(battery_status), battery_sub, &battery);
/* only consider battery voltage if system has been running 2s and battery voltage is valid */
- if (status.hil_state == HIL_STATE_OFF && hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
+ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
status.battery_voltage = battery.voltage_filtered_v;
status.battery_current = battery.current_a;
status.condition_battery_voltage_valid = true;