aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-03-28 10:44:28 +0400
committerAnton Babushkin <anton.babushkin@me.com>2014-03-28 10:44:28 +0400
commita991ebd8ca4aa1dc6fd69e307a74be6a93f4e6ff (patch)
tree6f96a4c1e8814cb9232b6b1f94a0f7be4d87116e /src/modules
parent83da4ae02dfc61d6a7f80ae40660826fbbca81be (diff)
parent9b1de5004c673ebe8bdf68f1b518565cccd6b05b (diff)
downloadpx4-firmware-a991ebd8ca4aa1dc6fd69e307a74be6a93f4e6ff.tar.gz
px4-firmware-a991ebd8ca4aa1dc6fd69e307a74be6a93f4e6ff.tar.bz2
px4-firmware-a991ebd8ca4aa1dc6fd69e307a74be6a93f4e6ff.zip
Merge branch 'master' into mpc_local_pos
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp11
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp93
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp4
-rw-r--r--src/modules/sdlog2/sdlog2.c1
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h3
-rw-r--r--src/modules/sensors/sensors.cpp7
-rw-r--r--src/modules/uORB/topics/differential_pressure.h5
-rw-r--r--src/modules/uORB/topics/sensor_combined.h2
8 files changed, 88 insertions, 38 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 7da062961..bc63c810b 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -119,6 +119,7 @@ extern struct system_load_s system_load;
#define POSITION_TIMEOUT 20000 /**< consider the local or global position estimate invalid after 20ms */
#define RC_TIMEOUT 100000
+#define RC_TIMEOUT_HIL 500000
#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
@@ -1099,8 +1100,16 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
}
+
+ /*
+ * XXX workaround:
+ * Prevent RC loss in HIL when sensors.cpp is only publishing sp_man at a low rate (e.g. 30Hz)
+ * which can trigger RC loss if the computer/simulator lags.
+ */
+ uint64_t rc_timeout = status.hil_state == HIL_STATE_ON ? RC_TIMEOUT_HIL : RC_TIMEOUT;
+
/* start RC input check */
- if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
+ if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + rc_timeout) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
status.rc_signal_found_once = true;
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 037999af7..4ca3840d4 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -71,6 +71,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/navigation_capabilities.h>
#include <drivers/drv_rc_input.h>
+#include <drivers/drv_pwm_output.h>
#include "mavlink_messages.h"
@@ -788,47 +789,79 @@ protected:
uint32_t mavlink_custom_mode;
get_mavlink_mode_state(status, pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
- /* set number of valid outputs depending on vehicle type */
- unsigned n;
+ if (mavlink_system.type == MAV_TYPE_QUADROTOR ||
+ mavlink_system.type == MAV_TYPE_HEXAROTOR ||
+ mavlink_system.type == MAV_TYPE_OCTOROTOR) {
+ /* set number of valid outputs depending on vehicle type */
+ unsigned n;
- switch (mavlink_system.type) {
- case MAV_TYPE_QUADROTOR:
- n = 4;
- break;
+ switch (mavlink_system.type) {
+ case MAV_TYPE_QUADROTOR:
+ n = 4;
+ break;
- case MAV_TYPE_HEXAROTOR:
- n = 6;
- break;
+ case MAV_TYPE_HEXAROTOR:
+ n = 6;
+ break;
- default:
- n = 8;
- break;
- }
+ default:
+ n = 8;
+ break;
+ }
- /* scale / assign outputs depending on system type */
- float out[8];
+ /* scale / assign outputs depending on system type */
+ float out[8];
- for (unsigned i = 0; i < 8; i++) {
- if (i < n) {
- if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- /* scale fake PWM out 900..1200 us to 0..1*/
- out[i] = (act->output[i] - 900.0f) / 1200.0f;
+ for (unsigned i = 0; i < 8; i++) {
+ if (i < n) {
+ if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ /* scale fake PWM out 900..2100 us to 0..1 for normal multirotors */
+ out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+
+ } else {
+ /* send 0 when disarmed */
+ out[i] = 0.0f;
+ }
} else {
- /* send 0 when disarmed */
- out[i] = 0.0f;
+ out[i] = -1.0f;
+ }
+ }
+
+ mavlink_msg_hil_controls_send(_channel,
+ hrt_absolute_time(),
+ out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
+ mavlink_base_mode,
+ 0);
+ } else {
+
+ /* fixed wing: scale all channels except throttle -1 .. 1
+ * because we know that we set the mixers up this way
+ */
+
+ float out[8];
+
+ const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
+
+ for (unsigned i = 0; i < 8; i++) {
+ if (i != 3) {
+ /* scale fake PWM out 900..2100 us to -1..+1 for normal channels */
+ out[i] = (act->output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
+
+ } else {
+
+ /* scale fake PWM out 900..2100 us to 0..1 for throttle */
+ out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
}
- } else {
- out[i] = -1.0f;
}
- }
- mavlink_msg_hil_controls_send(_channel,
- hrt_absolute_time(),
- out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
- mavlink_base_mode,
- 0);
+ mavlink_msg_hil_controls_send(_channel,
+ hrt_absolute_time(),
+ out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
+ mavlink_base_mode,
+ 0);
+ }
}
}
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 2c9cdbf24..dc6236a51 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -635,13 +635,15 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
hil_battery_status.timestamp = timestamp;
hil_battery_status.voltage_v = 11.1f;
+ hil_battery_status.voltage_filtered_v = 11.1f;
hil_battery_status.current_a = 10.0f;
+ hil_battery_status.discharged_mah = -1.0f;
if (_battery_pub > 0) {
orb_publish(ORB_ID(battery_status), _battery_pub, &hil_battery_status);
} else {
- _baro_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
+ _battery_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
}
}
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 36d309d6c..365890b35 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -1021,6 +1021,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa;
+ log_msg.body.log_SENS.diff_pres_filtered = buf.sensor.differential_pressure_filtered_pa;
LOGBUFFER_WRITE_AND_COUNT(SENS);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index fbfca76f7..5ed3624fd 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -92,6 +92,7 @@ struct log_SENS_s {
float baro_alt;
float baro_temp;
float diff_pres;
+ float diff_pres_filtered;
};
/* --- LPOS - LOCAL POSITION --- */
@@ -306,7 +307,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
- LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
+ LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
LOG_FORMAT(LPOS, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 520ea3137..91a8d5670 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1029,10 +1029,11 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
raw.differential_pressure_pa = _diff_pres.differential_pressure_pa;
raw.differential_pressure_timestamp = _diff_pres.timestamp;
+ raw.differential_pressure_filtered_pa = _diff_pres.differential_pressure_filtered_pa;
- _airspeed.timestamp = hrt_absolute_time();
- _airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
- _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar * 1e2f,
+ _airspeed.timestamp = _diff_pres.timestamp;
+ _airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_filtered_pa);
+ _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_filtered_pa + raw.baro_pres_mbar * 1e2f,
raw.baro_pres_mbar * 1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
/* announce the airspeed if needed, just publish else */
diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h
index 5d94d4288..3592c023c 100644
--- a/src/modules/uORB/topics/differential_pressure.h
+++ b/src/modules/uORB/topics/differential_pressure.h
@@ -54,8 +54,9 @@
struct differential_pressure_s {
uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
uint64_t error_count;
- float differential_pressure_pa; /**< Differential pressure reading */
- float max_differential_pressure_pa; /**< Maximum differential pressure reading */
+ float differential_pressure_pa; /**< Differential pressure reading */
+ float differential_pressure_filtered_pa; /**< Low pass filtered differential pressure reading */
+ float max_differential_pressure_pa; /**< Maximum differential pressure reading */
float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */
float temperature; /**< Temperature provided by sensor */
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index 92812efd4..cc25a83c3 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -104,6 +104,8 @@ struct sensor_combined_s {
float differential_pressure_pa; /**< Airspeed sensor differential pressure */
uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */
+ float differential_pressure_filtered_pa; /**< Low pass filtered airspeed sensor differential pressure reading */
+
};
/**