Skip to content

Commit

Permalink
Merge branch 'diff_press_filter' into diff_press_filter_use
Browse files Browse the repository at this point in the history
Conflicts:
	src/modules/sensors/sensors.cpp
  • Loading branch information
thomasgubler committed Mar 21, 2014
2 parents be349b9 + bc451ee commit 70b3a85
Show file tree
Hide file tree
Showing 39 changed files with 505 additions and 231 deletions.
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/11001_hexa_cox
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#
# UNTESTED UNTESTED!
#
# Generic 10 Hexa coaxial geometry
# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/12001_octo_cox
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Octo coaxial geometry
# Generic 10" Octo coaxial geometry
#
# Lorenz Meier <[email protected]>
#
Expand Down
31 changes: 30 additions & 1 deletion ROMFS/px4fmu_common/init.d/3031_phantom
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,38 @@
#
# Phantom FPV Flying Wing
#
# Simon Wilks <[email protected]>
# Simon Wilks <[email protected]>, Thomas Gubler <[email protected]>
#

sh /etc/init.d/rc.fw_defaults

if [ $DO_AUTOCONFIG == yes ]
then
param set FW_AIRSPD_MIN 13
param set FW_AIRSPD_TRIM 18
param set FW_AIRSPD_MAX 40
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.75
param set FW_L1_PERIOD 15
param set FW_PR_FF 0.2
param set FW_PR_I 0.005
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 0
param set FW_RR_FF 0.5
param set FW_RR_I 0.02
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.08
param set FW_R_LIM 70
param set FW_R_RMAX 0
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
param set FW_T_TIME_CONST 5
fi

set MIXER FMU_Q
42 changes: 42 additions & 0 deletions ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
#!nsh
#
# TBS Caipirinha Flying Wing
#
# Thomas Gubler <[email protected]>
#

sh /etc/init.d/rc.fw_defaults

if [ $DO_AUTOCONFIG == yes ]
then

# TODO: these are the X5 default parameters, update them to the caipi

param set FW_AIRSPD_MIN 15
param set FW_AIRSPD_TRIM 20
param set FW_AIRSPD_MAX 40
param set FW_ATT_TC 0.3
param set FW_L1_DAMPING 0.74
param set FW_L1_PERIOD 15
param set FW_PR_FF 0.3
param set FW_PR_I 0
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 0
param set FW_RR_FF 0.3
param set FW_RR_I 0
param set FW_RR_IMAX 0.2
param set FW_RR_P 0.03
param set FW_R_LIM 60
param set FW_R_RMAX 0
param set FW_T_HRATE_P 0.01
param set FW_T_RLL2THR 15
param set FW_T_SRATE_P 0.01
param set FW_T_TIME_CONST 5
fi

set MIXER FMU_Q
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/4001_quad_x
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Quad X geometry
# Generic 10" Quad X geometry
#
# Lorenz Meier <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/5001_quad_+
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Quad + geometry
# Generic 10" Quad + geometry
#
# Anton Babushkin <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/6001_hexa_x
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Hexa X geometry
# Generic 10" Hexa X geometry
#
# Anton Babushkin <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/7001_hexa_+
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Hexa + geometry
# Generic 10" Hexa + geometry
#
# Anton Babushkin <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/8001_octo_x
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Octo X geometry
# Generic 10" Octo X geometry
#
# Anton Babushkin <[email protected]>
#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/9001_octo_+
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!nsh
#
# Generic 10 Octo + geometry
# Generic 10" Octo + geometry
#
# Anton Babushkin <[email protected]>
#
Expand Down
5 changes: 5 additions & 0 deletions ROMFS/px4fmu_common/init.d/rc.autostart
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,11 @@ then
sh /etc/init.d/3034_fx79
fi

if param compare SYS_AUTOSTART 3100
then
sh /etc/init.d/3100_tbs_caipirinha
fi

#
# Quad X
#
Expand Down
2 changes: 2 additions & 0 deletions ROMFS/px4fmu_common/init.d/rc.fw_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,6 @@ then
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50
param set RC_SCALE_ROLL 1
param set RC_SCALE_PITCH 1
fi
15 changes: 12 additions & 3 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,6 @@ then
set HIL no
set VEHICLE_TYPE none
set MIXER none
set USE_IO yes
set OUTPUT_MODE none
set PWM_OUTPUTS none
set PWM_RATE none
Expand All @@ -129,6 +128,16 @@ then
else
set DO_AUTOCONFIG no
fi

#
# Set USE_IO flag
#
if param compare SYS_USE_IO 1
then
set USE_IO yes
else
set USE_IO no
fi

#
# Set parameters and env variables for selected AUTOSTART
Expand Down Expand Up @@ -466,7 +475,7 @@ then
sh /etc/init.d/rc.interface

# Start standard fixedwing apps
if [ LOAD_DEFAULT_APPS == yes ]
if [ $LOAD_DEFAULT_APPS == yes ]
then
sh /etc/init.d/rc.fw_apps
fi
Expand Down Expand Up @@ -525,7 +534,7 @@ then
sh /etc/init.d/rc.interface

# Start standard multicopter apps
if [ LOAD_DEFAULT_APPS == yes ]
if [ $LOAD_DEFAULT_APPS == yes ]
then
sh /etc/init.d/rc.mc_apps
fi
Expand Down
3 changes: 1 addition & 2 deletions src/drivers/ets_airspeed/ets_airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,6 @@ ETSAirspeed::measure()

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

return ret;
Expand Down Expand Up @@ -308,7 +307,7 @@ start(int i2c_bus)
g_dev = nullptr;
}

errx(1, "driver start failed");
errx(1, "no ETS airspeed sensor connected");
}

/**
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/md25/md25.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@
#include <arch/board/board.h>
#include <mavlink/mavlink_log.h>

#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/debug_key_value.h>
#include <drivers/drv_hrt.h>

Expand Down Expand Up @@ -587,7 +587,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu
float prev_revolution = md25.getRevolutions1();

// debug publication
control::UOrbPublication<debug_key_value_s> debug_msg(NULL,
uORB::Publication<debug_key_value_s> debug_msg(NULL,
ORB_ID(debug_key_value));

// sine wave for motor 1
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/md25/md25.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@

#include <poll.h>
#include <stdio.h>
#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>

Expand Down Expand Up @@ -270,7 +270,7 @@ class MD25 : public device::I2C
struct pollfd _controlPoll;

/** actuator controls subscription */
control::UOrbSubscription<actuator_controls_s> _actuators;
uORB::Subscription<actuator_controls_s> _actuators;

// local copy of data from i2c device
uint8_t _version;
Expand Down
Loading

0 comments on commit 70b3a85

Please sign in to comment.