mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-05-10 06:59:54 +08:00
added auto1 commands
This commit is contained in:
@@ -4,7 +4,7 @@
|
||||
+ Pixracer http://arsovtech.com/?page_id=1590
|
||||
* in Fixedwing (http://www.openuas.org/)
|
||||
+ Airframe to test the PX4 Pixracer v1 firmware while developing...
|
||||
E-Flite T28 Trojan fully equiped with Retractable gear and Flaps
|
||||
E-Flite T28 Trojan fully equiped with Retractable gear and flap
|
||||
+ Autopilot: PX4FMU 4.0 aka Pixracer v1.0
|
||||
+ Actuators: Regular digital servos
|
||||
+ GPS: Ublox M8N GNSS
|
||||
@@ -75,7 +75,7 @@ NOTES:
|
||||
<!-- <define name="RADIO_CONTROL_NB_CHANNEL" value="9"/> -->
|
||||
|
||||
<!-- Mode set one a three way switch -->
|
||||
<define name="RADIO_MODE" value="4"/> <!-- yes, already done by default if not redefined to something else-->
|
||||
<!-- Per defaulr already GEAR if not defined <define name="RADIO_MODE" value="RADIO_GEAR"/> --><!-- yes, already done by default if not redefined to something else-->
|
||||
<define name="RADIO_GEAR" value="RADIO_AUX1"/>
|
||||
<define name="RADIO_FLAP" value="RADIO_AUX2"/>
|
||||
<!-- <define name="SPEKTRUM_HAS_SOFT_BIND_PIN" value="1"/> -->
|
||||
@@ -162,8 +162,8 @@ NOTES:
|
||||
<configure name="AHRS_USE_MAGNETOMETER" value="FALSE"/> <!-- First autoflight set to false better make sure it works and is callibrated if set to TRUE -->
|
||||
<configure name="AHRS_ALIGNER_LED" value="2"/>
|
||||
<define name="AHRS_MAG_UPDATE_ALL_AXES" value="TRUE"/> <!-- with those high roll n pith angles better id calibrated well -->
|
||||
<define name="AHRS_USE_GPS_HEADING" value="TRUE"/> <!-- Use GPS course to update heading for time being,if FALSE data from magneto only, testing, brrrr... -->
|
||||
<define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="TRUE"/> <!-- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing)"-->
|
||||
<!-- TRUE by default <define name="AHRS_USE_GPS_HEADING" value="FALSE"/> --><!-- Use GPS course to update heading for time being,if FALSE data from magneto only, testing, brrrr... -->
|
||||
<!-- TRUE by default <define name="AHRS_GRAVITY_UPDATE_COORDINATED_TURN" value="FALSE"/>--> <!-- Compensation of centrifugal force via GPS speed (to fly in circles with a fixedwing)"-->
|
||||
<define name="AHRS_GPS_SPEED_IN_NEGATIVE_Z_DIRECTION" value="FALSE"/> <!-- AHRS_GRAVITY_UPDATE_COORDINATED_TURN assumes the GPS speed is in the X axis direction. Quadshot, DelftaCopter and other hybrids can have the GPS speed in the negative Z direction" -->
|
||||
<define name="AHRS_PROPAGATE_LOW_PASS_RATES" value="TRUE"/> <!-- apply a low pass filter on rotational velocity"-->
|
||||
<define name="AHRS_BIAS_UPDATE_HEADING_THRESHOLD" value="5.0"/> <!-- don't update gyro bias if heading deviation is above this threshold in degrees"-->
|
||||
@@ -266,7 +266,7 @@ NOTES:
|
||||
|
||||
<!-- ************************* MODULES ************************* -->
|
||||
<modules>
|
||||
<!-- <module name="auto1_commands"/>--><!-- NOT finished for NON intermcu to be able to set GEAR and FLAPS etc. in stabiized mode for easier testflights -->
|
||||
<module name="auto1_commands"/><!-- NOT finished for NON intermcu to be able to set GEAR and FLAP etc. in stabiized mode for easier testflights -->
|
||||
|
||||
<module name="baro_ms5611_spi" >
|
||||
<configure name="MS5611_SPI_DEV" value="spi1"/>
|
||||
@@ -352,9 +352,9 @@ NOTES:
|
||||
<!-- Just name a few, value can be used in e.g. flightplan -->
|
||||
<define name="LANINGGEAR_EXTEND" value="-MAX_PPRZ" />
|
||||
<define name="LANDINGGEAR_RETRACT" value="MAX_PPRZ" />
|
||||
<define name="FLAPS_FULL" value="-MAX_PPRZ" />
|
||||
<define name="FLAPS_HALF" value="-MAX_PPRZ/2" />
|
||||
<define name="FLAPS_NONE" value="0" /><!-- TODO hardware mod use full servo range -->
|
||||
<define name="FLAP_FULL" value="-MAX_PPRZ" />
|
||||
<define name="FLAP_HALF" value="-MAX_PPRZ/2" />
|
||||
<define name="FLAP_NONE" value="0" /><!-- TODO hardware mod use full servo range -->
|
||||
<define name="BEACON_ROTATE" value="MAX_PPRZ" />
|
||||
<define name="BEACON_FLASH" value="0" />
|
||||
<define name="BEACON_OFF" value="-MAX_PPRZ" />
|
||||
@@ -369,7 +369,7 @@ NOTES:
|
||||
<servo name="S_FLAP" no="5" min="1100" neutral="1500" max="1900"/>
|
||||
</servos>
|
||||
|
||||
<!--For mixed controlflaps -->
|
||||
<!--For mixed controls -->
|
||||
<section name="MIXER">
|
||||
<!-- just a tiny bit works well-->
|
||||
<define name="ASSIST_ROLL_WITH_RUDDER" value="0.09"/>
|
||||
@@ -395,7 +395,7 @@ NOTES:
|
||||
<!-- To still be able to use rudder in auto mode, which is handy with sidewind landing in auto1 stabilization mode only YAW
|
||||
Handy if in auto1 for sidewind stabilized crabbing landing, also for steering if someting not OK with course gains in Autonomous flight
|
||||
TODO disable again after strong wind sidewind autolanding is 100% tuned
|
||||
Note that in auto2 mode the Flaps and Gears are after test then controlable by flightplan conditions e.g landng block extend gear and flaps -->
|
||||
Note that in auto2 mode the Flap and Gear are after test then controlable by flightplan conditions e.g landng block extend gear and flap -->
|
||||
<set command="YAW" value="@YAW"/> <!-- TODO: Diable later -->
|
||||
<set command="GEAR" value="@GEAR"/> <!-- TODO: Diable later -->
|
||||
<set command="FLAP" value="@FLAP"/> <!-- TODO: Diable later -->
|
||||
@@ -444,7 +444,7 @@ NOTES:
|
||||
<define name="DEFAULT_GEAR" value="1100"/>
|
||||
<define name="DEFAULT_ROLL" value="10.0" unit="deg"/>
|
||||
<define name="DEFAULT_PITCH" value="-5.0" unit="deg"/>
|
||||
<!-- TODO Maybe extent flaps to landing position, testfly it first -->
|
||||
<!-- TODO Maybe extent flap to landing position, testfly it first -->
|
||||
<define name="HOME_RADIUS" value="DEFAULT_CIRCLE_RADIUS" unit="m"/>
|
||||
<define name="KILL_MODE_DISTANCE" value="MAX_DIST_FROM_HOME*1.3+HOME_RADIUS" unit="m"/><!-- improve value by default turn radius calc -->
|
||||
<define name="DELAY_WITHOUT_GPS" value="4" unit="s"/>
|
||||
@@ -656,7 +656,7 @@ NOTES:
|
||||
<define name="CLIMB_AIRSPEED" value="7." unit="m/s"/> <!-- TODO get best values -->
|
||||
<define name="TRACKING_AIRSPEED" value="20." unit="m/s"/> <!-- TODO get best values -->
|
||||
<define name="GLIDE_AIRSPEED" value="16." unit="m/s"/> <!-- TODO get best values -->
|
||||
<define name="STALL_AIRSPEED" value="12." unit="m/s"/> <!-- measue limit of plane in testflight and set 80% from this --> <!-- No flaps, an pct flp ratio-->
|
||||
<define name="STALL_AIRSPEED" value="12." unit="m/s"/> <!-- measue limit of plane in testflight and set 80% from this --> <!-- No flap, an pct flp ratio-->
|
||||
<define name="RACE_AIRSPEED" value="21." unit="m/s"/> <!-- TODO determine -->
|
||||
|
||||
<define name="MIN_SPEED_FOR_TAKEOFF" value="4." unit="m/s"/> <!-- TODO determine and change to make it for airspeed -->
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
Symlink
+1
@@ -0,0 +1 @@
|
||||
userconf/OPENUAS/openuas_control_panel.xml
|
||||
@@ -52,9 +52,12 @@
|
||||
#ifndef RADIO_YAW
|
||||
#define RADIO_YAW 3
|
||||
#endif
|
||||
|
||||
#ifndef RADIO_GEAR
|
||||
#define RADIO_GEAR 4
|
||||
#endif
|
||||
#ifndef RADIO_FLAP
|
||||
#define RADIO_FLAP 5
|
||||
#endif
|
||||
#define RADIO_AUX1 5
|
||||
#define RADIO_AUX2 6
|
||||
#define RADIO_AUX3 7
|
||||
|
||||
@@ -177,8 +177,8 @@ When a read-operation of an RTD resistance data register occurs, DRDY returns hi
|
||||
|
||||
/* MDL */
|
||||
// FIXME: Test n fix of not working
|
||||
#define SPI_SELECT_SLAVE1_PORT GPIOE
|
||||
#define SPI_SELECT_SLAVE1_PIN GPIO15 */
|
||||
//#define SPI_SELECT_SLAVE1_PORT GPIOE
|
||||
//#define SPI_SELECT_SLAVE1_PIN GPIO15 */
|
||||
|
||||
/* MPU_9250_CS on SPI1 */
|
||||
#define SPI_SELECT_SLAVE2_PORT GPIOC
|
||||
|
||||
@@ -28,12 +28,60 @@
|
||||
void periodic_auto1_commands(void)
|
||||
{
|
||||
// Copy Radio commands in AUTO1
|
||||
if (pprz_mode == PPRZ_MODE_AUTO1) {
|
||||
#ifdef COMMAND_HATCH
|
||||
#ifndef RADIO_HATCH
|
||||
#error auto1_commands COMMAND_HATCH needs RADIO_HATCH channel
|
||||
if (autopilot_get_mode() == PPRZ_MODE_AUTO1) {
|
||||
#ifdef COMMAND_GEAR
|
||||
#ifndef RADIO_GEAR
|
||||
#error auto1_commands COMMAND_GEAR needs RADIO_GEAR channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_HATCH, imcu_get_radio(RADIO_HATCH));
|
||||
imcu_set_command(COMMAND_GEAR, imcu_get_radio(RADIO_GEAR));
|
||||
#endif
|
||||
#ifdef COMMAND_FLAP
|
||||
#ifndef RADIO_FLAP
|
||||
#error auto1_commands COMMAND_FLAP needs RADIO_FLAP channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_FLAP, imcu_get_radio(RADIO_FLAP));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX1
|
||||
#ifndef RADIO_AUX1
|
||||
#error auto1_commands COMMAND_AUX1 needs RADIO_AUX1 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX1, imcu_get_radio(RADIO_AUX1));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX2
|
||||
#ifndef RADIO_AUX2
|
||||
#error auto1_commands COMMAND_AUX2 needs RADIO_AUX2 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX2, imcu_get_radio(RADIO_AUX2));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX3
|
||||
#ifndef RADIO_AUX3
|
||||
#error auto1_commands COMMAND_AUX1 needs RADIO_AUX3 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX3, imcu_get_radio(RADIO_AUX3));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX4
|
||||
#ifndef RADIO_AUX4
|
||||
#error auto1_commands COMMAND_AUX4 needs RADIO_AUX4 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX4, imcu_get_radio(RADIO_AUX4));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX5
|
||||
#ifndef RADIO_AUX5
|
||||
#error auto1_commands COMMAND_AUX5 needs RADIO_AUX5 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX5, imcu_get_radio(RADIO_AUX5));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX6
|
||||
#ifndef RADIO_AUX6
|
||||
#error auto1_commands COMMAND_AUX6 needs RADIO_AUX6 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX6, imcu_get_radio(RADIO_AUX6));
|
||||
#endif
|
||||
#ifdef COMMAND_AUX7
|
||||
#ifndef RADIO_AUX7
|
||||
#error auto1_commands COMMAND_AUX7 needs RADIO_AUX7 channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_AUX7, imcu_get_radio(RADIO_AUX7));
|
||||
#endif
|
||||
#ifdef COMMAND_BRAKE
|
||||
#ifndef RADIO_BRAKE
|
||||
@@ -41,11 +89,11 @@ void periodic_auto1_commands(void)
|
||||
#endif
|
||||
imcu_set_command(COMMAND_BRAKE, imcu_get_radio(RADIO_BRAKE));
|
||||
#endif
|
||||
#ifdef COMMAND_FLAPS
|
||||
#ifndef RADIO_FLAPS
|
||||
#error auto1_commands COMMAND_FLAPS needs RADIO_FLAPS channel
|
||||
#ifdef COMMAND_HATCH
|
||||
#ifndef RADIO_HATCH
|
||||
#error auto1_commands COMMAND_HATCH needs RADIO_HATCH channel
|
||||
#endif
|
||||
imcu_set_command(COMMAND_FLAPS, imcu_get_radio(RADIO_FLAPS));
|
||||
imcu_set_command(COMMAND_HATCH, imcu_get_radio(RADIO_HATCH));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user