Compare commits

...

247 Commits

Author SHA1 Message Date
Roman
f35e3335be - only use takeoff strategy when in auto mode
- after jumped takeoff set previous vel setpoint such
that thrust setpoint is continuous
2016-01-27 11:47:41 +01:00
Lorenz Meier
f2af8a5a5d IO Firmware: Reduce unnecessary buffer space 2016-01-27 09:56:20 +01:00
Lorenz Meier
b54a0308a7 IO: Do not allocate excessive UART buffers 2016-01-27 09:56:20 +01:00
Roman
ba169ce0b5 do not do jumped takeoff if already in air 2016-01-27 09:55:47 +01:00
Andreas Antener
3928924c43 RTL was broken by a recent change, revert
Revert "for multicopter landings make sure that the copter moves"

This reverts commit ad1058d3742bbfa9cbd16648aa2925fa1e618a55.
2016-01-26 15:53:52 +01:00
Lorenz Meier
5ea5ecf32b Limit manual yaw command properly. Fixes #3600 2016-01-26 14:08:43 +01:00
Roman
c9b1fb154d hotfix:
multirotors shouldn't use tailsitter recovery code.
2016-01-26 13:29:53 +01:00
Lorenz Meier
e11fff3011 Fix tests stack space 2016-01-26 12:58:17 +01:00
Lorenz Meier
17c3aa3bac MC att control: Slightly increase max yaw rate 2016-01-26 12:32:26 +01:00
Lorenz Meier
fcbd717200 Switch POSIX sitl to EKF2 per default 2016-01-25 22:42:53 +01:00
Lorenz Meier
6c13cef85e Lister: Add missing uint16 2016-01-25 21:46:07 +01:00
James Goppert
4cb1f8a440 Updated matrix for euler wrap fix. 2016-01-25 21:23:11 +01:00
Julian Oes
166f6e2e7a posix sitl: bring the pxh back 2016-01-25 21:22:10 +01:00
Julian Oes
6ce5e1be49 posix sitl: don't exit if a command fails 2016-01-25 19:03:48 +01:00
Julian Oes
563460444a ekf2: get the rad to deg conversion right 2016-01-25 19:03:16 +01:00
Julian Oes
28754d3f58 ekf2: don't reset GPS position in every loop 2016-01-25 19:03:16 +01:00
Lorenz Meier
9d5728b96f FMU: Default to 900 us pulses 2016-01-25 12:08:26 +01:00
Lorenz Meier
2e8accc6ff FMU driver: Only init pins right before using the for PWM. Prevents accidental pulses 2016-01-25 12:08:08 +01:00
Lorenz Meier
d32d533d11 FMUv4: Disable unused ADC channels 2016-01-25 12:07:38 +01:00
Lorenz Meier
9cccc0ec76 GPS: Do initial zero value publication to avoid corner cases 2016-01-25 09:30:45 +01:00
Lorenz Meier
6eac78d675 Sensors: Code style fix 2016-01-24 16:34:49 +01:00
Lorenz Meier
081da8bb7f Navigator: Force yaw pointing towards waypoint for all cases 2016-01-24 16:34:36 +01:00
Lorenz Meier
737fe1fc7f Always perform yaw SP generation, not only in multicopter mode 2016-01-24 16:30:21 +01:00
Lorenz Meier
b2237ce525 Current scaling: Employ per-board defaults 2016-01-24 16:02:21 +01:00
Julian Oes
4b55c5276e px_romfs_pruner.py: fix indenting 2016-01-24 15:46:29 +01:00
Julian Oes
443592136b px_romfs_pruner.py: PEP8ify and whitespace
- Changed from 8 spaces indent back to 4 which I find appropriate for
  Python.
- Fixed linelength to 80 chars.
2016-01-24 15:46:29 +01:00
Julian Oes
6e26d1b8dc px_romfs_pruner.py: ignore files starting with . 2016-01-24 15:46:29 +01:00
Lorenz Meier
9169a585bf Deprecate ROS target 2016-01-24 15:21:17 +01:00
Artem Sabadyr
a284b77c7b gps advertise fix 2016-01-24 15:03:41 +01:00
Lorenz Meier
06b496e257 Navigator: Only set acceptance radius based on navigation capabilities for fixed wing flight. 2016-01-24 14:08:41 +01:00
Lorenz Meier
fb21654807 PX4 airframes: Fix XML parser 2016-01-24 13:22:45 +01:00
Lorenz Meier
69d4b1b692 Fix config meta data 2016-01-24 13:22:25 +01:00
Mark Whitehorn
d96a17adfb missed some name changes from sPort to frsky 2016-01-24 11:22:18 +01:00
Mark Whitehorn
cfc3af8374 update fmu-v4 cmake config 2016-01-24 11:22:18 +01:00
Mark Whitehorn
527fe4b374 remove sPort_telemetry directory 2016-01-24 11:22:18 +01:00
Mark Whitehorn
c81c34b147 add sPort telemetry handling into frsky_telemetry daemon 2016-01-24 11:22:18 +01:00
Mark Whitehorn
8f8b4485f1 change rcS to start frsky_telemetry daemon for FMUv4 2016-01-24 11:22:18 +01:00
Mark Whitehorn
29d759768e clean up structure 2016-01-24 11:22:18 +01:00
Mark Whitehorn
42f9079683 move sPort_telemetry.c to src/drivers/frsky_telemetry and rename daemon
to frsky_telemetry
2016-01-24 11:22:18 +01:00
Mark Whitehorn
528e2826d5 run astyle 2016-01-24 11:22:18 +01:00
Mark Whitehorn
3b9ef1cef5 reduce reporting frequency for smartport sensors. reduces CPU load to
approx. 1%
2016-01-24 11:22:18 +01:00
Mark Whitehorn
4f55ae5306 add D type telemetry fallback to sPort_telemetry daemon 2016-01-24 11:22:18 +01:00
Mark Whitehorn
a402b3beeb change frsky_telemetry default port to USART8 for pixracer
add a 50msec timeout to poll calls in sPort_telemetry to prevent hangs
2016-01-24 11:22:18 +01:00
Mark Whitehorn
8d089d95d4 change baro altitude scaling to 100 to match OpenTX "custom" altitude
mode
2016-01-24 11:22:18 +01:00
Mark Whitehorn
52ebbda5ac add conditional start of sPort_telemetry daemon for FMUv4 to rcS 2016-01-24 11:22:18 +01:00
Mark Whitehorn
99286db832 running astyle inside QtCreator doesn't guarantee that travis will pass
format checks
2016-01-24 11:22:18 +01:00
Mark Whitehorn
6cb631716a corrected scales for OpenTX 2.1.7 as specified in the comments 2016-01-24 11:22:18 +01:00
Mark Whitehorn
4e4d1a98f6 update comments on scale factors 2016-01-24 11:22:18 +01:00
Mark Whitehorn
ea4937491b fix scale factor for VFAS: battery voltage report 2016-01-24 11:22:18 +01:00
Mark Whitehorn
bbc03731c7 initial implementation of 5 virtual sensors for Bat V,I, Baro alt, Fuel
and GPS speed. Voltage and current scaling can be set in OpenTX. Fuel is
in percent. Alt in meters. Need to look at what OpenTX wants for speed.
2016-01-24 11:22:18 +01:00
Mark Whitehorn
82bb0564e2 fix byte stuffing typo and add comments 2016-01-24 11:22:18 +01:00
Mark Whitehorn
8949a88f25 fix CRC calc and add battery voltage report 2016-01-24 11:22:18 +01:00
Mark Whitehorn
ff690dda80 increase priority of sPort_telemetry to 200 2016-01-24 11:22:18 +01:00
Mark Whitehorn
bb565f5d6a add sPort_telemetry cmd to fmu-v4 module list and change default port to ttyS6/usart8 2016-01-24 11:22:18 +01:00
Mark Whitehorn
214709dc89 move smartport telemetry to new module 2016-01-24 11:22:18 +01:00
Mark Whitehorn
47dcf71554 initial test of FrSky SmartPort telemetry 2016-01-24 11:22:18 +01:00
sander
9a8e94bb68 Reject mission when starting with LAND and vehicle is landed 2016-01-24 11:19:00 +01:00
James Goppert
759b107468 Update LPE sitl init script. 2016-01-24 05:16:02 -05:00
Lorenz Meier
bf03b8cb18 Yaw rate limit: use a lower limit for less twitching 2016-01-24 11:13:47 +01:00
Lorenz Meier
e2fd2f466e UDP testing for Linux folks 2016-01-24 11:13:47 +01:00
James Goppert
cfd8173687 Merge pull request #3574 from PX4/matrix_update
Matrix update.
2016-01-24 03:16:01 -05:00
James Goppert
c6d30315d9 Matrix update. 2016-01-24 02:45:24 -05:00
Lorenz Meier
03434a0b9e Start 3rd MAVLink instance on OSD port 2016-01-23 18:25:19 +01:00
Lorenz Meier
e17f344119 MAVLink: Enable 4 streams and fix OSD rate configuration 2016-01-23 18:25:19 +01:00
Lorenz Meier
c2aaeefa6c sdlog2: Log actuator output group 1 as well 2016-01-23 16:02:18 +01:00
Lorenz Meier
f52ce2001d Param lib: fix code style 2016-01-23 14:29:15 +01:00
Lorenz Meier
4b893053a0 param: Lock read operation 2016-01-23 13:32:52 +01:00
Lorenz Meier
b37082e390 MS5611: Run SPI bus faster 2016-01-23 13:32:42 +01:00
Lorenz Meier
99068aebac FMUv4: Run FRAM bus faster 2016-01-23 13:32:32 +01:00
Lorenz Meier
c18d31ce41 Param write: Support locking the bus 2016-01-23 13:23:53 +01:00
Lorenz Meier
1474ddbb78 MS5611: Ensure to set the lockmode at the right location 2016-01-23 13:23:32 +01:00
Roman
0102e47708 for multicopter landings make sure that the copter moves
to the landing waypoint first before the descending phase starts
2016-01-22 18:27:13 +01:00
Lorenz Meier
871b4b482e Do not enable new bus sync yet 2016-01-22 18:07:27 +01:00
Lorenz Meier
c659d7851f MS5611: Use the right locking mechanism on Pixracer 2016-01-22 17:12:13 +01:00
Lorenz Meier
e88367d722 SPI: Support setting the lock mode 2016-01-22 17:11:46 +01:00
tumbili
7a8ef6c0e4 elc ekf2:
support logging
2016-01-22 14:24:36 +01:00
Roman
c185a12c8e log ekf2 innovations and innovation variances 2016-01-22 14:24:36 +01:00
Roman
21f7641e8d log ekf2 estimator status 2016-01-22 14:24:36 +01:00
Roman
67eed88767 added message for ekf2 innovations message 2016-01-22 14:24:36 +01:00
Lorenz Meier
7452cfdf63 EKF2: Fix polling code 2016-01-22 14:21:19 +01:00
Lorenz Meier
f460e95554 Param: Increase robustness of default save command 2016-01-22 14:21:09 +01:00
Lorenz Meier
1cfa9d924d Fixed ekf2 stop / start routine 2016-01-22 12:07:17 +01:00
Lorenz Meier
08ef2e8a1c Param command: Increase stack as needed 2016-01-22 11:58:18 +01:00
Andreas Antener
9e2dd7aab6 landing without thrust limiting 2016-01-22 11:51:38 +01:00
Roman
7a8adaa591 multirotor landinging sudden fall protection:
remove condition which made activation of the protection
very unlikely
2016-01-22 11:51:38 +01:00
Lorenz Meier
c32938d2a8 EKF2: Update params only as they change 2016-01-22 11:45:29 +01:00
tumbili
93a9032f87 ekf2: parameter cleanup 2016-01-22 11:40:35 +01:00
tumbili
b6cf1b54f9 ecl ekf2: added default parameter values 2016-01-22 11:40:35 +01:00
Lorenz Meier
15b72045ce Param command: Auto-save after set 2016-01-22 11:36:14 +01:00
Lorenz Meier
3a43038583 Params: Provide set and save API 2016-01-22 11:35:56 +01:00
Lorenz Meier
85c49ff642 Commander: Do not save params on already saved param update 2016-01-22 11:33:40 +01:00
Lorenz Meier
19b81b9ab2 Commander: Rate-limit preflight check 2016-01-22 11:31:39 +01:00
David Sidrane
9c6f4de753 Fixes buffer overwrite on CONFIG_ARCH_BOARD_AEROCORE 2016-01-22 00:22:26 +01:00
Andreas Antener
4614511474 use set takeoff speed 2016-01-21 10:18:13 +01:00
Roman
7817924aef multirotor takeoff:
instead of altering the velocity setpoint for the vehicle to takeoff
use the thrust setpoint directly. this does not depend on the tuning of
the velocity loop.
2016-01-21 10:18:13 +01:00
Lorenz Meier
f918b0c992 Uploader: Make sure to warn about wrong board type 2016-01-21 09:34:54 +01:00
Roman
e6d2d17109 initialise topic structs properly 2016-01-21 07:25:18 +01:00
Lorenz Meier
4ce5d4e3e3 Make LPE_ENABLED available as default 2016-01-20 23:54:12 +01:00
Roman Bapst
93042eccb6 Merge pull request #3550 from PX4/level_horizon
fix level horizon feature:
2016-01-20 15:22:39 +01:00
tumbili
afb01e6d9a fix level horizon feature:
allow attitude to settle for a while if changes to the board rotation
parameters are done
2016-01-20 13:46:50 +01:00
Lorenz Meier
619548b10a MAVLink: Send for the first 4 seconds to localhost on UDP to not interfere with the network 2016-01-20 11:53:58 +01:00
Lorenz Meier
883148d3d1 Revert "Adjust to AUAV screwup on voltage / current pins"
This reverts commit 3c401c396c690228987df354a7a50bd46a12d790.
2016-01-20 11:13:24 +01:00
Lorenz Meier
a49dbbc9a8 Lister: Fix Clang compile error 2016-01-20 11:01:31 +01:00
Lorenz Meier
b8f11dee99 MAVLink: Code style 2016-01-20 10:59:39 +01:00
Lorenz Meier
83e45a1564 Re-instate UDP handling for MAVLink app 2016-01-20 10:59:25 +01:00
Lorenz Meier
3c401c396c Adjust to AUAV screwup on voltage / current pins 2016-01-20 10:47:50 +01:00
Lorenz Meier
cbde246f0a FMUv4: Remove non-existent airspeed sensing channel 2016-01-20 10:09:07 +01:00
sander
92c946dae1 New default PID's for QuadRanger 2016-01-19 22:14:46 +01:00
Lorenz Meier
0025ab7258 Sensors: Code style 2016-01-19 22:00:20 +01:00
Lorenz Meier
751a95deb8 Commander: Operate blue led on pixracer 2016-01-19 19:27:36 +01:00
Lorenz Meier
a76ecf3821 Remove differential pressure ADC 2016-01-19 19:27:21 +01:00
Lorenz Meier
cd37ffd0bf Do not sample pressure ADC if not configured 2016-01-19 19:27:05 +01:00
Lorenz Meier
d1cf8df2ad Initialize system power struct 2016-01-19 19:26:50 +01:00
Lorenz Meier
56957e7ee4 Improved listener tool 2016-01-19 19:26:31 +01:00
Lorenz Meier
9d239c10e5 Restore MAVLink network behaviour with fixed remote system approach 2016-01-18 23:19:51 +01:00
Kabir Mohammed
37cbb90930 Crosscompiler support 2016-01-18 22:42:42 +01:00
Mohammed Kabir
37ffb61afd changes to rpi2 configs 2016-01-18 22:42:35 +01:00
Mohammed Kabir
4351eb147c Add native RPi2 build config 2016-01-18 22:42:29 +01:00
Lorenz Meier
de88892f99 Update Matrix to fix QuRT build 2016-01-18 13:40:30 -08:00
Lorenz Meier
7ead4050d6 Hotfix for sock addr, but this is merely a workaround 2016-01-18 13:08:35 +01:00
Lorenz Meier
803f2ce035 Fix threshold param comment 2016-01-18 11:36:11 +01:00
Lorenz Meier
ab65a55fbf Change arming transfer to only set the register if the local configuration changed. Move its write operation to the fast rate so that arming / disarming is instantaneous 2016-01-18 11:36:11 +01:00
Lorenz Meier
f485b60f57 Kill switch: Fix logic to only trigger on on/off state of switch, not on/undefined. Remove debug output. 2016-01-18 11:36:11 +01:00
Lorenz Meier
cb2c8a1390 Fix list of files to check for code style 2016-01-18 11:36:11 +01:00
Mark Whitehorn
8cb472af31 add RC kill switch 2016-01-18 11:36:11 +01:00
Lorenz Meier
c802b86acc Sensors: Fix FMUv4 voltage 2016-01-18 10:24:10 +01:00
Lorenz Meier
bafa9bb6bb MAVLink: Fall back in altitude indication to baro if estimate is not available 2016-01-17 16:30:02 +01:00
Lorenz Meier
57b95916f5 MAVLink: Add stack space for interface 2016-01-17 16:29:36 +01:00
Roman Bapst
efd7e202f7 Merge pull request #3518 from PX4/mc_checks
multirotor mission feasibility checks:
2016-01-17 15:43:53 +01:00
tumbili
07fafc4913 multirotor mission feasibility checks:
make sure that the relative altitude of the takeoff waypoint is
at least one meter higher than the acceptance radius of the waypoint.
This makes sure that the takeoff waypoint is not reached before the vehicle
is at least one meter in the air.
2016-01-17 13:09:28 +01:00
Lorenz Meier
170f9aec49 Update standard VTOL model 2016-01-16 14:38:12 +01:00
Lorenz Meier
401af28b38 Ensure that UAVCAN_ENABLE is always present 2016-01-16 12:07:50 +01:00
Lorenz Meier
7ea41491e5 FMUv4: Fix code style 2016-01-15 23:48:18 +01:00
Roman Bapst
0db264bc79 Merge pull request #3519 from PX4/mc_pos_quick_fix
quick fix:
2016-01-15 23:29:15 +01:00
Lorenz Meier
415e42f5de MS5611: Use baro SPI device 2016-01-15 22:44:22 +01:00
Lorenz Meier
0910cb3256 FMUv4: Add baro SPI bus define 2016-01-15 22:34:20 +01:00
Lorenz Meier
e663b60c69 FMUv2: Add baro SPI bus define 2016-01-15 22:34:09 +01:00
tumbili
be1db2ced5 quick fix:
Remove throttle non-increase condition for landing since this has lead to
quads falling out of the sky.
2016-01-15 16:15:27 +01:00
Sander Smeets
4ab39725dd Merge pull request #3517 from sanderux/master
QuadRanger airframe
2016-01-15 11:58:24 +01:00
Sander Smeets
c77a2acb93 QuadRanger airframe 2016-01-15 10:22:29 +00:00
Lorenz Meier
c0e88e262c Drop man min throttle to 8% since its a continous user complaint 2016-01-14 23:50:37 +01:00
Lorenz Meier
c0bc721778 Add missing define for DSM 2016-01-14 18:48:42 +01:00
Roman Bapst
b26fc1f089 fix waypoint handling in position control 2016-01-14 18:30:30 +01:00
Lorenz Meier
9fb29d3a38 FMU: Add RC input definition for each RC protocol 2016-01-14 17:55:55 +01:00
Lorenz Meier
5bd4495a78 Added input_rc SUMD defines 2016-01-14 17:55:55 +01:00
Lorenz Meier
c7767dfe7e RC: Add constants for FMU input 2016-01-14 17:55:55 +01:00
Mark Whitehorn
5a93e68918 fix code style 2016-01-14 17:55:55 +01:00
Mark Whitehorn
ab1bbb9ed8 remove extraneous rescan tests 2016-01-14 17:55:55 +01:00
Mark Whitehorn
4d7fe08069 fix code style 2016-01-14 17:55:55 +01:00
Mark Whitehorn
5d588d98be change CMake CONFIG to fmu-v2 and THREADS to 4 2016-01-14 17:55:55 +01:00
Mark Whitehorn
df5cb5472d configure GPIO_SBUS_INV for PixRacer R12 2016-01-14 17:55:54 +01:00
Mark Whitehorn
ecbcfe838b clean up, change SPI2 clock back to 12MHz and remove debug prints 2016-01-14 17:55:54 +01:00
Mark Whitehorn
ab71af6053 fix spi select logic 2016-01-14 17:55:54 +01:00
Mark Whitehorn
4952d05652 debugging ms5611 on spi2 2016-01-14 17:55:54 +01:00
Mark Whitehorn
32626b57a4 add missing #ifdef 2016-01-14 17:55:54 +01:00
Mark Whitehorn
47207b8fc8 set FMU_RC_OUTPUT high for all non-SBUS modes 2016-01-14 17:55:54 +01:00
Mark Whitehorn
5cf78cd450 configure usart6 TX for RC out
add RC_OUT pin to FMUv4 config
2016-01-14 17:55:54 +01:00
Mark Whitehorn
e0bbbd356f add SUMD decoder to RCscan 2016-01-14 17:55:53 +01:00
Mark Whitehorn
3d185e18e9 remove warnx in set_rc_scan_state 2016-01-14 17:55:53 +01:00
Mark Whitehorn
eb36eac137 reduce scan interval to 100msec 2016-01-14 17:55:53 +01:00
Mark Whitehorn
9eecca6a71 add string value struct for RC_SCAN enum 2016-01-14 17:55:53 +01:00
Mark Whitehorn
425169921c begin adding DSM bind function 2016-01-14 17:55:53 +01:00
Mark Whitehorn
ca2e9e7be1 handle PPM input with RC_SERIAL_PORT undefined 2016-01-14 17:55:53 +01:00
Mark Whitehorn
72156d9cd6 add macro to control RC input inverter
remove redundant variable
2016-01-14 17:55:53 +01:00
Mark Whitehorn
71a3e3713c move PPM input disable into scan case for PPM; PPM input is now enabled only while in RC_SCAN_PPM state 2016-01-14 17:55:52 +01:00
Mark Whitehorn
434ce85937 lock RC scan on first detection and fill in default values for fields not in DSM record
pull serial port read out of sbus and dsm input methods

clean up scanning code and add STM24
2016-01-14 17:55:52 +01:00
Mark Whitehorn
02030d9b36 scan working for SBUS and DSM 2016-01-14 17:55:52 +01:00
Mark Whitehorn
0f3878a48a DSM input tested OK with DX7 2016-01-14 17:55:52 +01:00
Mark Whitehorn
af42f454f7 fix sbus for pixracer beta 2016-01-14 17:55:52 +01:00
Andreas Antener
05b23a8b54 disable pos/vel control during mission in transitions 2016-01-14 16:07:01 +01:00
tumbili
0d1872f223 support building standard vtol plane in SITL gazebo 2016-01-14 16:07:01 +01:00
tumbili
5fb6c75a2a added mixer for standard quad vtol plane in SITL gazebo 2016-01-14 16:07:01 +01:00
tumbili
f2e7d5ca77 simulator: support for standard vtol plane 2016-01-14 16:07:01 +01:00
tumbili
2dab23ba04 pwm_out_sim: scale controls to correct range 2016-01-14 16:07:01 +01:00
tumbili
960a233fe9 added startup script for standard vtol plane in SITL 2016-01-14 16:07:01 +01:00
tumbili
ee71a0d761 updated sitl_gazebo: support standard quad vtol plane 2016-01-14 16:07:01 +01:00
Lorenz Meier
dd58dcfb91 Fix CMake version check 2016-01-14 12:48:42 +01:00
Lorenz Meier
67bba2065e ROMFS: Update airframe configs 2016-01-14 00:43:36 +01:00
Lorenz Meier
4437727b97 Airframes XML: Generate new icons 2016-01-14 00:43:23 +01:00
Lorenz Meier
30a86f4b79 FMU: Flag params requiring a reboot 2016-01-13 21:20:54 +01:00
Lorenz Meier
0f78c28aca PX4IO: Flag params requiring a reboot 2016-01-13 21:20:41 +01:00
Lorenz Meier
3e27189026 Sensor params: Flag params requiring a reboot 2016-01-13 21:20:21 +01:00
Lorenz Meier
9f4e6e3208 Set reboot required tag for cam trigger 2016-01-13 21:14:50 +01:00
Lorenz Meier
1772cbe5e0 Support reboot_required tag 2016-01-13 21:14:35 +01:00
Lorenz Meier
a2758eadb6 Automate initial submodule update 2016-01-13 11:50:27 +01:00
Roman Bapst
181cbd383c tailsitter gazebo: lower max climb/descend velocity 2016-01-12 13:40:33 +01:00
Lorenz Meier
2c786e21f4 Update Matrix lib to fix isfinite call 2016-01-12 12:16:24 +01:00
Lorenz Meier
e1ce681960 Update Matrix lib for CI 2016-01-12 11:52:00 +01:00
Lorenz Meier
e21062c6db Updated Matrix lib 2016-01-12 11:04:53 +01:00
Lorenz Meier
7d7333cdea Better output on submodule check fail 2016-01-12 10:33:24 +01:00
Lorenz Meier
e9dd2aec48 Further git submodule improvements 2016-01-12 10:18:05 +01:00
Lorenz Meier
365ef883e3 Check submodules during each build 2016-01-12 10:14:15 +01:00
James Goppert
c40c91bedc Updated matrix for quaternion merge. 2016-01-11 22:12:32 -06:00
Lorenz Meier
21b99b408c Yaw fix: increase threshold 2016-01-11 11:58:13 +01:00
Lorenz Meier
79e7059eaf Fix yaw when in manual mode during arming 2016-01-11 11:58:13 +01:00
Lorenz Meier
f99d052582 Fix submodule force. Fixes #3490. 2016-01-11 09:27:48 +01:00
nopeppermint
78f9bb79f1 more spelling mistakes 2016-01-11 08:38:09 +01:00
Stefan
ed081ef60b correct link to developer guide
correct link to developer guide
2016-01-11 08:37:43 +01:00
Stefan
47786c8585 Update mavlink_main.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
3dc4411592 Update sensors.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
1742cce6f6 Update commander.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
6e1bf506ad Update dq_rem.c
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
41abe9221e Update main.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
d5c6fde5bc Update px4_posix.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
70e7f1bec6 Update px4_spi.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
07973bf87a Update px4_nodehandle.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
c341f94e5d Update gimbal_params.c
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
b97b3c68cb Update mtk.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
c42b0e7201 Update camera_trigger.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
4ab4f1edc7 Update pwm_input.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
abf03c1c9d Update hott_sensors.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
54677cd223 Update messages.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
1d1ad3e9ed Update messages.h
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
86ca7d8cfc Update drv_hrt.c
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
5c1b84f16a Update ms5611_i2c.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
8701e0ba78 Update test_mathlib.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
b274a3f6d1 Update test_eigen.cpp
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
9f009d0615 Update UserGuide.md
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
9197b85cfe Update rc_parameter_map.msg
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
caf0121f95 Update manual_control_setpoint.msg
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
fb702b7c48 Update input_rc.msg
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
902b774091 Update mavlink_px4.py
spelling mistakes
2016-01-11 08:37:43 +01:00
Stefan
9d7b3bbff1 update ublox Protocol Specification links
update ublox Protocol Specification links
2016-01-11 08:37:43 +01:00
Andreas Antener
7e7b21cbdc use raw parameter floats if mission item is a mission command 2016-01-11 08:19:00 +01:00
Andreas Antener
b0333e3e95 allow transition commands in auto mode 2016-01-11 08:19:00 +01:00
Lorenz Meier
77782bd254 Navigator: Support transition command and digicam command in missions 2016-01-11 08:19:00 +01:00
Lorenz Meier
e1125ce9d3 Add digicam commands 2016-01-11 08:19:00 +01:00
Roman Bapst
2207986a1e Merge pull request #3485 from PX4/ekf2_blockparam
Ekf2 blockparam
2016-01-11 07:30:20 +01:00
Lorenz Meier
ecc53488dd Commander: Allow commandline takeoff if already armed 2016-01-11 00:40:40 +01:00
Lorenz Meier
4d36cb848f Fix excessive DriverFramework log level 2016-01-11 00:38:05 +01:00
Lorenz Meier
a355bdeea3 Fix MAVLink radio status flow control 2016-01-10 23:24:33 +01:00
Roman
88b2c6c78d blockparam: added support for external parameter copy 2016-01-10 21:25:17 +01:00
Roman
0510d2cb56 fixed code style 2016-01-10 21:14:58 +01:00
Roman
8a9b27f8f3 ecl ekf: added parameter interface 2016-01-10 21:14:58 +01:00
Roman
fe07079367 added parameter interface to ekf2 2016-01-10 21:14:58 +01:00
Lorenz Meier
b22c05a19d Update DriverFramework and make mutex optional 2016-01-10 20:54:26 +01:00
Lorenz Meier
9674c611b3 Updated DriverFramework, fixes NuttX build 2016-01-10 20:54:26 +01:00
Mark Charlebois
caab016425 Updated cmake_hexagon
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
2016-01-10 20:54:26 +01:00
Mark Charlebois
a8c49809fa Fixes for other qurt builds to use QURT_BUNDLE
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
2016-01-10 20:54:26 +01:00
Mark Charlebois
f22c574b87 Integrated cmake_hexagon for qurt build
Still a WIP since the IDL file needs to be replace with the
muorb IDL file.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
2016-01-10 20:54:26 +01:00
Lorenz Meier
4b659f1995 Fix naming of Solo config 2016-01-10 16:18:52 +01:00
Lorenz Meier
1cdb2d3209 PWM command: Ensure we have enough stack 2016-01-10 16:11:30 +01:00
Lorenz Meier
83339a2de0 Remove unmaintained fixed wing controller 2016-01-10 13:57:00 +01:00
Lorenz Meier
dd883d2c9b Update README.md
More URL fixes from @peppermint
2016-01-09 23:07:41 +01:00
Stefan
36a8bcc12e Update README.md
in my opinion https://px4.io and https://discuss.px4.io is not a working webpage
http://px4.io and http://discuss.px4.io are working
2016-01-09 22:49:22 +01:00
Lorenz Meier
41f36aa99f Enable debug key/value stream by default 2016-01-09 16:59:37 +01:00
Lorenz Meier
055a17f2e1 Updated links in README 2016-01-09 16:59:22 +01:00
162 changed files with 2725 additions and 2053 deletions

3
.gitmodules vendored
View File

@ -34,3 +34,6 @@
[submodule "src/lib/ecl"]
path = src/lib/ecl
url = https://github.com/PX4/ecl.git
[submodule "cmake/cmake_hexagon"]
path = cmake/cmake_hexagon
url = https://github.com/ATLFlight/cmake_hexagon

View File

@ -93,6 +93,7 @@ env:
- PX4_AWS_BUCKET=px4-travis
script:
- git submodule update --init --recursive
- make check_format
- arm-none-eabi-gcc --version
- echo 'Building POSIX Firmware..' && make posix_sitl_default

View File

@ -16,7 +16,7 @@ git checkout -b mydescriptivebranchname
### Edit and build the code
The [developer guide](http://px4.io/dev/start) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](http://px4.io/dev/code_style) when editing files.
The [developer guide](http://dev.px4.io/) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](http://px4.io/dev/code_style) when editing files.
### Commit your changes

View File

@ -281,7 +281,7 @@ TYPEDEF_HIDES_STRUCT = NO
# causing a significant performance penality.
# If the system has enough physical memory increasing the cache will improve the
# performance by keeping more symbols in memory. Note that the value works on
# a logarithmic scale so increasing the size by one will rougly double the
# a logarithmic scale so increasing the size by one will roughly double the
# memory usage. The cache size is given by this formula:
# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0,
# corresponding to a cache size of 2^16 = 65536 symbols

View File

@ -48,7 +48,7 @@ Download QGC from http://qgroundcontrol.org/downloads and install using the wind
## PX4
### Platfrom Requirements
### Platform Requirements
Linux or Eagle with a working IP interface (?? does this need further instructions?)
### Build Host Requirements

View File

@ -109,7 +109,9 @@ endif
# describe how to build a cmake config
define cmake-build
+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(PWD)/build_$@/Makefile ]; then rm -rf $(PWD)/build_$@; fi
+@if [ ! -e $(PWD)/build_$@/CMakeCache.txt ]; then git submodule update --init --recursive --force && mkdir -p $(PWD)/build_$@ && cd $(PWD)/build_$@ && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1); fi
+git submodule init
+Tools/check_submodules.sh
+@if [ ! -e $(PWD)/build_$@/CMakeCache.txt ]; then git submodule sync && git submodule init && mkdir -p $(PWD)/build_$@ && cd $(PWD)/build_$@ && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1); fi
+$(PX4_MAKE) -C $(PWD)/build_$@ $(PX4_MAKE_ARGS) $(ARGS)
endef
@ -152,7 +154,8 @@ posix_sitl_ekf2:
$(call cmake-build,$@)
ros_sitl_default:
$(call cmake-build,$@)
@echo "This target is deprecated. Use make 'posix_sitl_default gazebo' instead."
# $(call cmake-build,$@)
qurt_eagle_travis:
$(call cmake-build,$@)
@ -168,6 +171,12 @@ qurt_eagle_default:
posix_eagle_default:
$(call cmake-build,$@)
posix_rpi2_default:
$(call cmake-build,$@)
posix_rpi2_release:
$(call cmake-build,$@)
posix: posix_sitl_default
@ -193,7 +202,8 @@ clean:
# targets handled by cmake
cmake_targets = test upload package package_source debug debug_tui debug_ddd debug_io debug_io_tui debug_io_ddd check_weak \
run_cmake_config config gazebo gazebo_gdb gazebo_lldb jmavsim \
jmavsim_gdb jmavsim_lldb gazebo_gdb_iris gazebo_lldb_tailsitter gazebo_iris gazebo_tailsitter
jmavsim_gdb jmavsim_lldb gazebo_gdb_iris gazebo_lldb_tailsitter gazebo_iris gazebo_tailsitter \
gazebo_gdb_standard_vtol gazebo_lldb_standard_vtol gazebo_standard_vtol
$(foreach targ,$(cmake_targets),$(eval $(call cmake-targ,$(targ))))
.PHONY: clean

View File

@ -9,33 +9,22 @@ This repository contains the [PX4 Flight Core](http://px4.io), with the main app
* Official Website: http://px4.io
* License: BSD 3-clause (see [LICENSE.md](https://github.com/PX4/Firmware/blob/master/LICENSE.md))
* Supported airframes (more experimental are supported):
* [Multicopters](http://px4.io/platforms/multicopters/start)
* [Fixed wing](http://px4.io/platforms/planes/start)
* [VTOL](http://px4.io/platforms/vtol/start)
* Binaries (always up-to-date from master):
* [Downloads](http://px4.io/firmware/downloads)
* [Multicopters](http://px4.io/portfolio_category/multicopter/)
* [Fixed wing](http://px4.io/portfolio_category/vtol/)
* [VTOL](http://px4.io/portfolio_category/plane/)
* Releases
* [Downloads](https://github.com/PX4/Firmware/releases)
* Forum / Mailing list: [Google Groups](http://groups.google.com/group/px4users)
### Users ###
Please refer to the [user documentation](https://pixhawk.org/users/start) for flying drones with the PX4 flight stack.
Please refer to the [user documentation](http://px4.io) and [user forum](http://discuss.px4.io) for flying drones with the PX4 flight stack.
### Developers ###
Contributing guide:
* [CONTRIBUTING.md](https://github.com/PX4/Firmware/blob/master/CONTRIBUTING.md)
* [PX4 Contribution Guide](http://px4.io/dev/contributing)
* [Developer Forum / Mailing list](http://groups.google.com/group/px4users)
* [Guide for Contributions](https://github.com/PX4/Firmware/blob/master/CONTRIBUTING.md)
* [Developer guide](http://dev.px4.io)
Software in the Loop guide:
Use software in the loop [to get started with the codebase](https://pixhawk.org/dev/simulation/native_sitl).
Developer guide:
http://dev.px4.io
Testing guide:
http://px4.io/dev/unit_tests
This repository contains code supporting these boards:
* [Snapdragon Flight](http://dev.px4.io/hardware-snapdragon.html)
@ -44,8 +33,3 @@ This repository contains code supporting these boards:
* FMUv4.x (Pixhawk X and [Pixracer](http://dev.px4.io/hardware-pixracer.html))
* AeroCore (v1 and v2)
* STM32F4Discovery (basic support) [Tutorial](https://pixhawk.org/modules/stm32f4discovery)
## NuttShell (NSH) ##
NSH usage documentation:
http://px4.io/users/serial_connection

View File

@ -2,7 +2,7 @@
#
# @name Duorotor Tailsitter
#
# @type VTOL Tailsitter
# @type VTOL Duo Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#

View File

@ -2,7 +2,7 @@
#
# @name Quadrotor X Tailsitter
#
# @type VTOL Tailsitter
# @type VTOL Quad Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#

View File

@ -2,7 +2,7 @@
#
# @name Quadrotor + Tailsitter
#
# @type VTOL Tailsitter
# @type VTOL Quad Tailsitter
#
# @maintainer Roman Bapst <roman@px4.io>
#

View File

@ -0,0 +1,53 @@
#!nsh
#
# @name QuadRanger
#
# @type Standard VTOL
#
# @maintainer Sander Smeets <sander@droneslab.com>
#
sh /etc/init.d/rc.vtol_defaults
if [ $AUTOCNF == yes ]
then
param set VT_TYPE 2
param set VT_MOT_COUNT 4
param set VT_TRANS_THR 0.75
param set PWM_AUX_REV1 1
param set PWM_AUX_REV2 1
param set MC_ROLL_P 7.0
param set MC_ROLLRATE_P 0.25
param set MC_ROLLRATE_I 0.002
param set MC_ROLLRATE_D 0.003
param set MC_ROLLRATE_FF 0.0
param set MC_PITCH_P 7.0
param set MC_PITCHRATE_P 0.23
param set MC_PITCHRATE_I 0.002
param set MC_PITCHRATE_D 0.003
param set MC_PITCHRATE_FF 0.0
param set MC_YAW_P 2.8
param set MC_YAW_FF 0.5
param set MC_YAWRATE_P 0.22
param set MC_YAWRATE_I 0.02
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_FF 0.0
fi
set MIXER vtol_quad_x
set PWM_OUT 12345678
set MIXER_AUX vtol_AAERT
set PWM_AUX_RATE 50
set PWM_AUX_OUT 1234
set PWM_AUX_DISARMED 1000
set PWM_AUX_MIN 1000
set PWM_AUX_MAX 2000
set MAV_TYPE 22
param set VT_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 2

View File

@ -2,7 +2,7 @@
#
# @name Applied Aeronautics Albatross
#
# @type Standard Plane
# @type Plane A-Tail
#
# @output MAIN1 aileron right
# @output MAIN2 aileron left

View File

@ -1,6 +1,6 @@
#!nsh
#
# @name Generic Quadrotor X config
# @name 3DR Solo
#
# @type Quadrotor x
#

View File

@ -550,7 +550,7 @@ then
# Avoid using ttyS1 for MAVLink on FMUv4
if ver hwcmp PX4FMU_V4
then
set MAVLINK_F "-r 1200 -d /dev/ttyS2"
set MAVLINK_F "-r 1200 -d /dev/ttyS1"
# Start MAVLink on Wifi (ESP8266 port)
mavlink start -r 800000 -b 921600 -d /dev/ttyS0
fi
@ -560,6 +560,12 @@ then
mavlink start $MAVLINK_F
unset MAVLINK_F
if ver hwcmp PX4FMU_V4
then
# Start MAVLink on OSD (TELEM2 port)
mavlink start -r 1200 -d /dev/ttyS2 -b 57600 -m osd
fi
#
# MAVLink onboard / TELEM2
#
@ -835,6 +841,11 @@ then
fi
fi
if ver hwcmp PX4FMU_V4
then
frsky_telemetry start -d /dev/ttyS6
fi
if ver hwcmp PX4FMU_V2
then
# Check for flow sensor - as it is a background task, launch it last

View File

@ -0,0 +1,24 @@
Mixer for standard vtol plane (SITL) with motor x configuration
=========================================================
This file defines a single mixer for a standard vtol plane (SITL gazebo) with motors in X configuration.
The plane has two ailerons and one elevator. The ailerons and elevator are treated as elevons
in order to make the standard vtol simulation compatible with the tailsitter simulation.
R: 4x 10000 10000 10000 0
# mixer for the elevons
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 5000 5000 0 -10000 10000
S: 1 1 -5000 -5000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 5000 5000 0 -10000 10000
S: 1 1 5000 5000 0 -10000 10000
# mixer for the pusher/puller throttle
M: 1
O: 10000 10000 0 -10000 10000
S: 1 3 0 20000 -10000 -10000 10000

View File

@ -6,7 +6,7 @@ then
exit 1;
fi
if [[ $cmake_ver == *"2.8"* ]] || [[ $cmake_ver == *"2.9"* ]] || [[ $cmake_ver == *"3.0"* ]] || [[ $cmake_ver == *"3.1"* ]]
if [[ $cmake_ver == *" 2.8"* ]] || [[ $cmake_ver == *" 2.9"* ]] || [[ $cmake_ver == *" 3.0"* ]] || [[ $cmake_ver == *" 3.1"* ]]
then
exit 1;
fi

View File

@ -25,7 +25,6 @@ for fn in $(find src/examples \
src/modules/uORB \
src/modules/bottle_drop \
src/modules/dataman \
src/modules/fixedwing_backside \
src/modules/segway \
src/modules/local_position_estimator \
src/modules/unit_test \

81
Tools/check_submodules.sh Executable file
View File

@ -0,0 +1,81 @@
#!/usr/bin/env bash
[ -n "$GIT_SUBMODULES_ARE_EVIL" ] && {
# GIT_SUBMODULES_ARE_EVIL is set, meaning user doesn't want submodules
echo "Skipping submodules. NUTTX_SRC is set to $NUTTX_SRC"
exit 0
}
if [ -f src/modules/uavcan/libuavcan/CMakeLists.txt ]
then
echo "Git submodule config valid."
else
git submodule update --init --recursive
fi
GITSTATUS=$(git status)
function check_git_submodule {
if [ -d $1 ];
then
SUBMODULE_STATUS=$(git submodule summary "$1")
STATUSRETVAL=$(echo $SUBMODULE_STATUS | grep -A20 -i "$1" | grep "<")
if [ -z "$STATUSRETVAL" ]; then
echo "Checked $1 submodule, correct version found"
else
echo -e "\033[31mChecked $1 submodule, ACTION REQUIRED:\033[0m"
echo ""
echo -e "New commits required:"
echo -e "$SUBMODULE_STATUS"
echo ""
echo ""
echo -e " *******************************************************************************"
echo -e " * \033[31mIF YOU DID NOT CHANGE THIS FILE (OR YOU DON'T KNOW WHAT A SUBMODULE IS):\033[0m *"
echo -e " * \033[31mHit 'u' and <ENTER> to update ALL submodules and resolve this.\033[0m *"
echo -e " * (performs \033[94mgit submodule update --init --recursive\033[0m) *"
echo -e " *******************************************************************************"
echo ""
echo ""
echo -e " Only for EXPERTS:"
echo -e " $1 submodule is not in the recommended version."
echo -e " Hit 'y' and <ENTER> to continue the build with this version. Hit <ENTER> to resolve manually."
echo -e " Use \033[94mgit add $1 && git commit -m 'Updated $1'\033[0m to choose this version (careful!)"
echo ""
read user_cmd
if [ "$user_cmd" == "y" ]
then
echo "Continuing build with manually overridden submodule.."
else
if [ "$user_cmd" == "u" ]
then
git submodule update --init --recursive
echo "Submodule fixed, continuing build.."
else
echo "Build aborted."
exit 1
fi
fi
fi
else
git submodule update --init --recursive;
git submodule update;
fi
}
check_git_submodule NuttX
check_git_submodule Tools/gencpp
check_git_submodule Tools/genmsg
check_git_submodule Tools/jMAVSim
check_git_submodule Tools/sitl_gazebo
check_git_submodule cmake/cmake_hexagon
check_git_submodule mavlink/include/mavlink/v1.0
check_git_submodule src/lib/DriverFramework
check_git_submodule src/lib/dspal
check_git_submodule src/lib/ecl
check_git_submodule src/lib/matrix
check_git_submodule src/modules/uavcan/libuavcan
check_git_submodule unittests/googletest
exit 0

View File

@ -136,12 +136,12 @@ extern "C" __EXPORT int listener_main(int argc, char *argv[]);
int listener_main(int argc, char *argv[]) {
int sub = -1;
orb_id_t ID;
if(argc < 3) {
printf("need at least two arguments: topic name, number of messages to print\\n");
if(argc < 2) {
printf("need at least two arguments: topic name. [optional number of messages to print]\\n");
return 1;
}
""")
print("\tunsigned num_msgs = atoi(argv[2]);")
print("\tunsigned num_msgs = (argc > 2) ? atoi(argv[2]) : 1;")
print("\tif (strncmp(argv[1],\"%s\",50) == 0) {" % messages[0])
print("\t\tsub = orb_subscribe(ORB_ID(%s));" % messages[0])
print("\t\tID = ORB_ID(%s);" % messages[0])
@ -154,9 +154,11 @@ for index,m in enumerate(messages[1:]):
print("\t\tstruct %s_s container;" % m)
print("\t\tmemset(&container, 0, sizeof(container));")
print("\t\tbool updated;")
print("\t\tfor (unsigned i = 0; i < num_msgs; i++) {")
print("\t\tunsigned i = 0;")
print("\t\twhile(i < num_msgs) {")
print("\t\t\torb_check(sub,&updated);")
print("\t\t\tupdated = true;")
print("\t\t\tif (i == 0) { updated = true; } else { usleep(500); }")
print("\t\t\ti++;")
print("\t\t\tif (updated) {")
print("\t\tprintf(\"\\nTOPIC: %s #%%d\\n\", i);" % m)
print("\t\t\torb_copy(ID,sub,&container);")
@ -190,9 +192,15 @@ for index,m in enumerate(messages[1:]):
elif item[0] == "int32":
print("\t\t\tprintf(\"%s: %%d\\n\",container.%s);" % (item[1], item[1]))
elif item[0] == "uint32":
print("\t\t\tprintf(\"%s: %%d\\n\",container.%s);" % (item[1], item[1]))
elif item[0] == "uint8":
print("\t\t\tprintf(\"%s: %%u\\n\",container.%s);" % (item[1], item[1]))
elif item[0] == "int16":
print("\t\t\tprintf(\"%s: %%d\\n\",(int)container.%s);" % (item[1], item[1]))
elif item[0] == "uint16":
print("\t\t\tprintf(\"%s: %%u\\n\",(unsigned)container.%s);" % (item[1], item[1]))
elif item[0] == "int8":
print("\t\t\tprintf(\"%s: %%d\\n\",(int)container.%s);" % (item[1], item[1]))
elif item[0] == "uint8":
print("\t\t\tprintf(\"%s: %%u\\n\",(unsigned)container.%s);" % (item[1], item[1]))
elif item[0] == "bool":
print("\t\t\tprintf(\"%s: %%s\\n\",container.%s ? \"True\" : \"False\");" % (item[1], item[1]))
print("\t\t\t}")

View File

@ -752,7 +752,7 @@ class MAVLink_gps_raw_int_message(MAVLink_message):
'''
The global position, as returned by the Global Positioning
System (GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value. See
estimate of the system, but rather a RAW sensor value. See
message GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS frame).
'''
@ -2812,7 +2812,7 @@ class MAVLink(object):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value.
estimate of the system, but rather a RAW sensor value.
See message GLOBAL_POSITION for the global position
estimate. Coordinate frame is right-handed, Z-axis up
(GPS frame).
@ -2837,7 +2837,7 @@ class MAVLink(object):
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value.
estimate of the system, but rather a RAW sensor value.
See message GLOBAL_POSITION for the global position
estimate. Coordinate frame is right-handed, Z-axis up
(GPS frame).

View File

@ -28,29 +28,55 @@ class XMLOutput():
xml_group = ET.SubElement(xml_parameters, "airframe_group")
xml_group.attrib["name"] = group.GetName()
if (group.GetName() == "Standard Plane"):
xml_group.attrib["image"] = "AirframeStandardPlane.png"
xml_group.attrib["image"] = "Plane"
elif (group.GetName() == "Flying Wing"):
xml_group.attrib["image"] = "AirframeFlyingWing.png"
xml_group.attrib["image"] = "FlyingWing"
elif (group.GetName() == "Quadrotor x"):
xml_group.attrib["image"] = "AirframeQuadRotorX.png"
xml_group.attrib["image"] = "QuadRotorX"
elif (group.GetName() == "Quadrotor +"):
xml_group.attrib["image"] = "AirframeQuadRotorPlus.png"
xml_group.attrib["image"] = "QuadRotorPlus"
elif (group.GetName() == "Hexarotor x"):
xml_group.attrib["image"] = "AirframeHexaRotorX.png"
xml_group.attrib["image"] = "HexaRotorX"
elif (group.GetName() == "Hexarotor +"):
xml_group.attrib["image"] = "AirframeHexaRotorPlus.png"
xml_group.attrib["image"] = "HexaRotorPlus"
elif (group.GetName() == "Octorotor +"):
xml_group.attrib["image"] = "AirframeOctoRotorPlus.png"
xml_group.attrib["image"] = "OctoRotorPlus"
elif (group.GetName() == "Octorotor x"):
xml_group.attrib["image"] = "AirframeOctoRotorX.png"
xml_group.attrib["image"] = "OctoRotorX"
elif (group.GetName() == "Octorotor Coaxial"):
xml_group.attrib["image"] = "OctoRotorXCoaxial"
elif (group.GetName() == "Quadrotor Wide"):
xml_group.attrib["image"] = "AirframeQuadRotorH.png"
xml_group.attrib["image"] = "QuadRotorWide"
elif (group.GetName() == "Quadrotor H"):
xml_group.attrib["image"] = "AirframeQuadRotorH.png"
xml_group.attrib["image"] = "QuadRotorH"
elif (group.GetName() == "Simulation"):
xml_group.attrib["image"] = "AirframeSimulation.png"
xml_group.attrib["image"] = "AirframeSimulation"
elif (group.GetName() == "Plane A-Tail"):
xml_group.attrib["image"] = "PlaneATail"
elif (group.GetName() == "VTOL Duo Tailsitter"):
xml_group.attrib["image"] = "VTOLDuoRotorTailSitter"
elif (group.GetName() == "Standard VTOL"):
xml_group.attrib["image"] = "VTOLPlane"
elif (group.GetName() == "VTOL Quad Tailsitter"):
xml_group.attrib["image"] = "VTOLQuadRotorTailSitter"
elif (group.GetName() == "VTOL Tiltrotor"):
xml_group.attrib["image"] = "VTOLTiltRotor"
elif (group.GetName() == "Coaxial Helicopter"):
xml_group.attrib["image"] = "HelicopterCoaxial"
elif (group.GetName() == "Hexarotor Coaxial"):
xml_group.attrib["image"] = "Y6A"
elif (group.GetName() == "Y6B"):
xml_group.attrib["image"] = "Y6B"
elif (group.GetName() == "Tricopter Y-"):
xml_group.attrib["image"] = "YMinus"
elif (group.GetName() == "Tricopter Y+"):
xml_group.attrib["image"] = "YPlus"
elif (group.GetName() == "Rover"):
xml_group.attrib["image"] = "Rover"
elif (group.GetName() == "Boat"):
xml_group.attrib["image"] = "Boat"
else:
xml_group.attrib["image"] = ""
xml_group.attrib["image"] = "AirframeUnknown"
for param in group.GetParams():
if (last_param_name == param.GetName() and not board_specific_param_set) or last_param_name != param.GetName():
xml_param = ET.SubElement(xml_group, "airframe")

View File

@ -107,7 +107,7 @@ class SourceParser(object):
re_remove_dots = re.compile(r'\.+$')
re_remove_carriage_return = re.compile('\n+')
valid_tags = set(["group", "board", "min", "max", "unit", "decimal"])
valid_tags = set(["group", "board", "min", "max", "unit", "decimal", "reboot_required"])
# Order of parameter groups
priority = {

View File

@ -1,8 +1,7 @@
#!/usr/bin/env python
############################################################################
#
# Copyright (C) 2014 PX4 Development Team. All rights reserved.
# Author: Julian Oes <joes@student.ethz.ch>
# Copyright (C) 2014-2015 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
@ -37,48 +36,53 @@
"""
px_romfs_pruner.py:
Delete all comments and newlines before ROMFS is converted to an image
@author: Julian Oes <julian@oes.ch>
"""
from __future__ import print_function
import argparse, re
import argparse
import re
import os
def main():
# Parse commandline arguments
parser = argparse.ArgumentParser(description="ROMFS pruner.")
parser.add_argument('--folder', action="store",
help="ROMFS scratch folder.")
args = parser.parse_args()
# Parse commandline arguments
parser = argparse.ArgumentParser(description="ROMFS pruner.")
parser.add_argument('--folder', action="store", help="ROMFS scratch folder.")
args = parser.parse_args()
print("Pruning ROMFS files.")
print("Pruning ROMFS files.")
# go through
for (root, dirs, files) in os.walk(args.folder):
for file in files:
# only prune text files
if ".zip" in file or ".bin" in file or ".swp" in file \
or ".data" in file or ".DS_Store" in file \
or file.startswith("."):
continue
# go through
for (root, dirs, files) in os.walk(args.folder):
for file in files:
# only prune text files
if ".zip" in file or ".bin" in file or ".swp" in file or ".data" in file or ".DS_Store" in file:
continue
file_path = os.path.join(root, file)
file_path = os.path.join(root, file)
# read file line by line
pruned_content = ""
with open(file_path, "rU") as f:
for line in f:
# handle mixer files differently than startup files
if file_path.endswith(".mix"):
if line.startswith(("Z:", "M:", "R: ", "O:", "S:")):
pruned_content += line
else:
if not line.isspace() and not line.strip().startswith("#"):
pruned_content += line
# overwrite old scratch file
with open(file_path, "wb") as f:
pruned_content = re.sub("\r\n", "\n", pruned_content)
f.write(pruned_content.encode("ascii", errors='strict'))
# read file line by line
pruned_content = ""
with open(file_path, "rU") as f:
for line in f:
# handle mixer files differently than startup files
if file_path.endswith(".mix"):
if line.startswith(("Z:", "M:", "R: ", "O:", "S:")):
pruned_content += line
else:
if not line.isspace() \
and not line.strip().startswith("#"):
pruned_content += line
# overwrite old scratch file
with open(file_path, "wb") as f:
pruned_content = re.sub("\r\n", "\n", pruned_content)
f.write(pruned_content.encode("ascii", errors='strict'))
if __name__ == '__main__':
main()
main()

View File

@ -449,8 +449,9 @@ class uploader(object):
if self.board_type != fw.property('board_id'):
msg = "Firmware not suitable for this board (board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id'))
print("WARNING: %s" % msg)
if args.force:
print("WARNING: %s" % msg)
print("FORCED WRITE, FLASHING ANYWAY!")
else:
raise IOError(msg)
if self.fw_maxsize < fw.property('image_size'):

@ -1 +1 @@
Subproject commit 6af47249caefa3ddb6de2c31ae061aff1858fd0e
Subproject commit 16f7fb37619e4af772a543f7bac62bef5126347b

1
cmake/cmake_hexagon Submodule

@ -0,0 +1 @@
Subproject commit 829f22eff345c934ca8939b2385768ca5e33794c

View File

@ -266,6 +266,10 @@ function(px4_add_module)
add_library(${MODULE} STATIC EXCLUDE_FROM_ALL ${SRCS})
if(${OS} STREQUAL "qurt" )
set_property(TARGET ${MODULE} PROPERTY POSITION_INDEPENDENT_CODE TRUE)
endif()
if(MAIN)
set_target_properties(${MODULE} PROPERTIES
COMPILE_DEFINITIONS PX4_MAIN=${MAIN}_app_main)

View File

@ -0,0 +1,47 @@
include(posix/px4_impl_posix)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
set(config_module_list
drivers/device
platforms/common
platforms/posix/px4_layer
platforms/posix/work_queue
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/esc_calib
systemcmds/reboot
systemcmds/topic_listener
systemcmds/perf
modules/uORB
modules/param
modules/systemlib
modules/systemlib/mixer
modules/sensors
modules/mavlink
modules/attitude_estimator_q
modules/position_estimator_inav
modules/navigator
modules/vtol_att_control
modules/mc_pos_control
modules/mc_att_control
modules/land_detector
modules/fw_att_control
modules/fw_pos_control_l1
modules/dataman
modules/sdlog2
modules/commander
modules/controllib
lib/mathlib
lib/mathlib/math/filter
lib/conversion
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/launchdetection
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
)

View File

@ -0,0 +1,56 @@
include(posix/px4_impl_posix)
if ("${RPI_TOOLCHAIN_DIR}" STREQUAL "")
set(RPI_TOOLCHAIN_DIR /opt/rpi_toolchain)
endif()
set(CMAKE_PROGRAM_PATH
"${RPI_TOOLCHAIN_DIR}/gcc-linaro-arm-linux-gnueabihf-raspbian/bin"
${CMAKE_PROGRAM_PATH}
)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-linux-gnueabihf.cmake)
set(config_module_list
drivers/device
platforms/common
platforms/posix/px4_layer
platforms/posix/work_queue
systemcmds/param
systemcmds/mixer
systemcmds/ver
systemcmds/esc_calib
systemcmds/reboot
systemcmds/topic_listener
systemcmds/perf
modules/uORB
modules/param
modules/systemlib
modules/systemlib/mixer
modules/sensors
modules/mavlink
modules/attitude_estimator_q
modules/position_estimator_inav
modules/navigator
modules/vtol_att_control
modules/mc_pos_control
modules/mc_att_control
modules/land_detector
modules/fw_att_control
modules/fw_pos_control_l1
modules/dataman
modules/sdlog2
modules/commander
modules/controllib
lib/mathlib
lib/mathlib/math/filter
lib/conversion
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/launchdetection
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
)

View File

@ -34,6 +34,7 @@ set(config_module_list
modules/mavlink
modules/attitude_estimator_ekf
modules/attitude_estimator_q
modules/ekf2
modules/ekf_att_pos_estimator
modules/position_estimator_inav
modules/navigator

View File

@ -11,17 +11,18 @@ include(qurt/px4_impl_qurt)
#include_directories(${HEXAGON_DRIVERS_ROOT}/inc)
# For Actual flight we need to link against the driver dynamic libraries
set(target_libraries
-L${HEXAGON_DRIVERS_ROOT}/libs
#set(target_libraries
# -L${HEXAGON_DRIVERS_ROOT}/libs
# The plan is to replace these with our drivers
# mpu9x50
# uart_esc
# csr_gps
# rc_receiver
)
# )
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
#

View File

@ -1,6 +1,8 @@
include(qurt/px4_impl_qurt)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
drivers/device

View File

@ -1,6 +1,7 @@
include(qurt/px4_impl_qurt)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
drivers/device

View File

@ -1,6 +1,8 @@
include(qurt/px4_impl_qurt)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
drivers/device

View File

@ -20,7 +20,8 @@ set(target_libraries
)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
#

View File

@ -1,6 +1,7 @@
include(qurt/px4_impl_qurt)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
drivers/device

View File

@ -3,7 +3,8 @@ include(qurt/px4_impl_qurt)
# Run a full link with build stubs to make sure qurt target isn't broken
set(QURT_ENABLE_STUBS "1")
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-hexagon-7.2.10.cmake)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/toolchain/Toolchain-qurt.cmake)
include(${CMAKE_SOURCE_DIR}/cmake/cmake_hexagon/qurt_app.cmake)
set(config_module_list
drivers/device

View File

@ -172,16 +172,13 @@ function(px4_os_add_flags)
set(added_definitions
-D__PX4_QURT
-D__PX4_POSIX
-D__DF_QURT
-include ${PX4_INCLUDE_DIR}visibility.h
)
# Add the toolchain specific flags
set(added_cflags ${QURT_CMAKE_C_FLAGS})
set(added_cxx_flags ${QURT_CMAKE_CXX_FLAGS})
set(added_cflags -O0)
set(added_cxx_flags -O0)
# FIXME @jgoppert - how to work around issues like this?
# Without changing global variables?
# Clear -rdynamic flag which fails for hexagon
set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")
set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "")

View File

@ -1,254 +0,0 @@
#
# Copyright (C) 2015 Mark Charlebois. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
include(CMakeForceCompiler)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
include(common/px4_base)
if ("$ENV{HEXAGON_TOOLS_ROOT}" STREQUAL "")
message(FATAL_ERROR
"The HexagonTools version 7.2.10 must be installed and the environment variable HEXAGON_TOOLS_ROOT must be set"
"(e.g. export HEXAGON_TOOLS_ROOT=/opt/HEXAGON_Tools/7.2.10/Tools)")
else()
set(HEXAGON_TOOLS_ROOT $ENV{HEXAGON_TOOLS_ROOT})
endif()
macro (list2string out in)
set(list ${ARGV})
list(REMOVE_ITEM list ${out})
foreach(item ${list})
set(${out} "${${out}} ${item}")
endforeach()
endmacro(list2string)
set(V_ARCH "v5")
set(CROSSDEV "hexagon-")
set(HEXAGON_BIN ${HEXAGON_TOOLS_ROOT}/bin)
set(HEXAGON_LIB_DIR ${HEXAGON_TOOLS_ROOT}/gnu/hexagon/lib)
set(HEXAGON_ISS_DIR ${HEXAGON_TOOLS_ROOT}/lib/iss)
set(TOOLSLIB ${HEXAGON_TOOLS_ROOT}/target/hexagon/lib/${V_ARCH}/G0)
# Use the HexagonTools compiler (7.2.10)
set(CMAKE_C_COMPILER ${HEXAGON_BIN}/${CROSSDEV}clang)
set(CMAKE_CXX_COMPILER ${HEXAGON_BIN}/${CROSSDEV}clang++)
set(CMAKE_AR ${HEXAGON_BIN}/${CROSSDEV}ar CACHE FILEPATH "Archiver")
set(CMAKE_RANLIB ${HEXAGON_BIN}/${CROSSDEV}ranlib)
set(CMAKE_LINKER ${HEXAGON_BIN}/${CROSSDEV}ld.qcld)
set(CMAKE_NM ${HEXAGON_BIN}/${CROSSDEV}nm)
set(CMAKE_OBJDUMP ${HEXAGON_BIN}/${CROSSDEV}objdump)
set(CMAKE_OBJCOPY ${HEXAGON_BIN}/${CROSSDEV}objcopy)
list2string(HEXAGON_INCLUDE_DIRS
-I${HEXAGON_TOOLS_ROOT}/target/hexagon/include
)
#set(DYNAMIC_LIBS -Wl,${TOOLSLIB}/pic/libstdc++.a)
#set(MAXOPTIMIZATION -O0)
# Base CPU flags for each of the supported architectures.
#
set(ARCHCPUFLAGS
-m${V_ARCH}
-G0
)
add_definitions(
-D_PID_T -D_UID_T -D_TIMER_T
-Dnoreturn_function=
-D_HAS_C9X
-D__EXPORT=
-Drestrict=
-D_DEBUG
-Wno-error=shadow
)
# optimisation flags
#
set(ARCHOPTIMIZATION
-O0
-g
-fno-strict-aliasing
-fdata-sections
-fno-zero-initialized-in-bss
)
# Language-specific flags
#
set(ARCHCFLAGS
-std=gnu99
-D__CUSTOM_FILE_IO__
)
set(ARCHCXXFLAGS
-fno-exceptions
-fno-rtti
-std=c++11
-fno-threadsafe-statics
-DCONFIG_WCHAR_BUILTIN
-D__CUSTOM_FILE_IO__
)
set(ARCHWARNINGS
-Wall
-Wextra
-Werror
-Wno-unused-parameter
-Wno-unused-function
-Wno-unused-variable
-Wno-gnu-array-member-paren-init
-Wno-cast-align
-Wno-missing-braces
-Wno-strict-aliasing
# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
)
# C-specific warnings
#
set(ARCHCWARNINGS
${ARCHWARNINGS}
-Wstrict-prototypes
-Wnested-externs
)
# C++-specific warnings
#
set(ARCHWARNINGSXX
${ARCHWARNINGS}
-Wno-missing-field-initializers
)
exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-libgcc-file-name OUTPUT_VARIABLE LIBGCC)
exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-file-name=libm.a OUTPUT_VARIABLE LIBM)
set(EXTRA_LIBS ${EXTRA_LIBS} ${LIBM})
# Flags we pass to the C compiler
#
list2string(CFLAGS
${ARCHCFLAGS}
${ARCHCWARNINGS}
${ARCHOPTIMIZATION}
${ARCHCPUFLAGS}
${ARCHINCLUDES}
${INSTRUMENTATIONDEFINES}
${ARCHDEFINES}
${EXTRADEFINES}
${EXTRACFLAGS}
${HEXAGON_INCLUDE_DIRS}
)
# Flags we pass to the C++ compiler
#
list2string(CXXFLAGS
${ARCHCXXFLAGS}
${ARCHWARNINGSXX}
${ARCHOPTIMIZATION}
${ARCHCPUFLAGS}
${ARCHXXINCLUDES}
${INSTRUMENTATIONDEFINES}
${ARCHDEFINES}
${EXTRADEFINES}
${EXTRACXXFLAGS}
${HEXAGON_INCLUDE_DIRS}
)
# Flags we pass to the assembler
#
list2string(AFLAGS
${CFLAGS}
-D__ASSEMBLY__
${EXTRADEFINES}
${EXTRAAFLAGS}
)
# Set cmake flags
#
list2string(CMAKE_C_FLAGS
${CMAKE_C_FLAGS}
${CFLAGS}
)
set(QURT_CMAKE_C_FLAGS ${CMAKE_C_FLAGS} CACHE STRING "cflags")
message(STATUS "CMAKE_C_FLAGS: -${CMAKE_C_FLAGS}-")
list2string(CMAKE_CXX_FLAGS
${CMAKE_CXX_FLAGS}
${CXXFLAGS}
)
set(QURT_CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} CACHE STRING "cxxflags")
message(STATUS "CMAKE_CXX_FLAGS: -${CMAKE_CXX_FLAGS}-")
# Flags we pass to the linker
#
list2string(CMAKE_EXE_LINKER_FLAGS
-g
-mv5
-mG0lib
-G0
-fpic
-shared
-Wl,-Bsymbolic
-Wl,--wrap=malloc
-Wl,--wrap=calloc
-Wl,--wrap=free
-Wl,--wrap=realloc
-Wl,--wrap=memalign
-Wl,--wrap=__stack_chk_fail
-lc
${EXTRALDFLAGS}
)
# where is the target environment
set(CMAKE_FIND_ROOT_PATH get_file_component(${C_COMPILER} PATH))
set(CMAKE_C_COMPILER_ID, "Clang")
set(CMAKE_CXX_COMPILER_ID, "Clang")
# search for programs in the build host directories
set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
# for libraries and headers in the target directories
set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
# The Hexagon compiler doesn't support the -rdynamic flag and this is set
# in the base cmake scripts. We have to redefine the __linux_compiler_gnu
# macro for cmake 2.8 to work
set(__LINUX_COMPILER_GNU 1)
macro(__linux_compiler_gnu lang)
set(CMAKE_SHARED_LIBRARY_LINK_${lang}_FLAGS "")
endmacro()

View File

@ -1,249 +0,0 @@
#
# Copyright (C) 2015 Mark Charlebois. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
include(CMakeForceCompiler)
list(APPEND CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake)
include(common/px4_base)
if(NOT HEXAGON_TOOLS_ROOT)
set(HEXAGON_TOOLS_ROOT /opt/6.4.05)
endif()
if(NOT HEXAGON_SDK_ROOT)
set(HEXAGON_SDK_ROOT /opt/Hexagon_SDK)
endif()
macro (list2string out in)
set(list ${ARGV})
list(REMOVE_ITEM list ${out})
foreach(item ${list})
set(${out} "${${out}} ${item}")
endforeach()
endmacro(list2string)
set(V_ARCH "v5")
set(CROSSDEV "hexagon-")
set(HEXAGON_BIN ${HEXAGON_TOOLS_ROOT}/gnu/bin)
set(HEXAGON_CLANG_BIN ${HEXAGON_TOOLS_ROOT}/qc/bin)
set(HEXAGON_LIB_DIR ${HEXAGON_TOOLS_ROOT}/gnu/hexagon/lib)
set(HEXAGON_ISS_DIR ${HEXAGON_TOOLS_ROOT}/qc/lib/iss)
set(TOOLSLIB ${HEXAGON_TOOLS_ROOT}/dinkumware/lib/$(V_ARCH)/G0)
set(QCTOOLSLIB ${HEXAGON_TOOLS_ROOT}/qc/lib/$(V_ARCH)/G0)
# Use the HexagonTools compiler (6.4.05)
set(CMAKE_C_COMPILER ${HEXAGON_CLANG_BIN}/${CROSSDEV}clang)
set(CMAKE_CXX_COMPILER ${HEXAGON_CLANG_BIN}/${CROSSDEV}clang++)
set(CMAKE_AR ${HEXAGON_BIN}/${CROSSDEV}ar CACHE FILEPATH "Archiver")
set(CMAKE_RANLIB ${HEXAGON_BIN}/${CROSSDEV}ranlib)
set(CMAKE_LINKER ${HEXAGON_BIN}/${CROSSDEV}ld)
set(CMAKE_NM ${HEXAGON_BIN}/${CROSSDEV}nm)
set(CMAKE_OBJDUMP ${HEXAGON_BIN}/${CROSSDEV}objdump)
set(CMAKE_OBJCOPY ${HEXAGON_BIN}/${CROSSDEV}objcopy)
list2string(HEXAGON_INCLUDE_DIRS
-I${HEXAGON_TOOLS_ROOT}/gnu/hexagon/include
-I${HEXAGON_SDK_ROOT}/inc
-I${HEXAGON_SDK_ROOT}/inc/stddef
)
#set(DYNAMIC_LIBS -Wl,${TOOLSLIB}/pic/libstdc++.a)
#set(MAXOPTIMIZATION -O0)
# Base CPU flags for each of the supported architectures.
#
set(ARCHCPUFLAGS
-m${V_ARCH}
-G0
)
add_definitions(
-D_PID_T -D_UID_T -D_TIMER_T
-Dnoreturn_function=
-D__EXPORT=
-Drestrict=
-D_DEBUG
-Wno-error=shadow
)
# optimisation flags
#
set(ARCHOPTIMIZATION
-O0
-g
-fno-strict-aliasing
-fdata-sections
-fpic
-fno-zero-initialized-in-bss
)
# Language-specific flags
#
set(ARCHCFLAGS
-std=gnu99
-D__CUSTOM_FILE_IO__
)
set(ARCHCXXFLAGS
-fno-exceptions
-fno-rtti
-std=c++11
-fno-threadsafe-statics
-DCONFIG_WCHAR_BUILTIN
-D__CUSTOM_FILE_IO__
)
set(ARCHWARNINGS
-Wall
-Wextra
-Werror
-Wno-unused-parameter
-Wno-unused-function
-Wno-unused-variable
-Wno-gnu-array-member-paren-init
-Wno-cast-align
-Wno-missing-braces
-Wno-strict-aliasing
# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
)
# C-specific warnings
#
set(ARCHCWARNINGS
${ARCHWARNINGS}
-Wstrict-prototypes
-Wnested-externs
)
# C++-specific warnings
#
set(ARCHWARNINGSXX
${ARCHWARNINGS}
-Wno-missing-field-initializers
)
exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-libgcc-file-name OUTPUT_VARIABLE LIBGCC)
exec_program(${CMAKE_CXX_COMPILER} ${CMAKE_CURRENT_SOURCE_DIR} ARGS -print-file-name=libm.a OUTPUT_VARIABLE LIBM)
set(EXTRA_LIBS ${EXTRA_LIBS} ${LIBM})
# Flags we pass to the C compiler
#
list2string(CFLAGS
${ARCHCFLAGS}
${ARCHCWARNINGS}
${ARCHOPTIMIZATION}
${ARCHCPUFLAGS}
${ARCHINCLUDES}
${INSTRUMENTATIONDEFINES}
${ARCHDEFINES}
${EXTRADEFINES}
${EXTRACFLAGS}
${HEXAGON_INCLUDE_DIRS}
)
# Flags we pass to the C++ compiler
#
list2string(CXXFLAGS
${ARCHCXXFLAGS}
${ARCHWARNINGSXX}
${ARCHOPTIMIZATION}
${ARCHCPUFLAGS}
${ARCHXXINCLUDES}
${INSTRUMENTATIONDEFINES}
${ARCHDEFINES}
${EXTRADEFINES}
${EXTRACXXFLAGS}
${HEXAGON_INCLUDE_DIRS}
)
# Flags we pass to the assembler
#
list2string(AFLAGS
${CFLAGS}
-D__ASSEMBLY__
${EXTRADEFINES}
${EXTRAAFLAGS}
)
# Set cmake flags
#
list2string(CMAKE_C_FLAGS
${CMAKE_C_FLAGS}
${CFLAGS}
)
set(QURT_CMAKE_C_FLAGS ${CMAKE_C_FLAGS} CACHE STRING "cflags")
message(STATUS "CMAKE_C_FLAGS: -${CMAKE_C_FLAGS}-")
list2string(CMAKE_CXX_FLAGS
${CMAKE_CXX_FLAGS}
${CXXFLAGS}
)
set(QURT_CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} CACHE STRING "cxxflags")
message(STATUS "CMAKE_CXX_FLAGS: -${CMAKE_CXX_FLAGS}-")
# Flags we pass to the linker
#
list2string(CMAKE_EXE_LINKER_FLAGS
-g
-mv5
-mG0lib
-G0
-fpic
-shared
-Wl,-Bsymbolic
-Wl,--wrap=malloc
-Wl,--wrap=calloc
-Wl,--wrap=free
-Wl,--wrap=realloc
-Wl,--wrap=memalign
-Wl,--wrap=__stack_chk_fail
-lc
${EXTRALDFLAGS}
)
# where is the target environment
set(CMAKE_FIND_ROOT_PATH get_file_component(${C_COMPILER} PATH))
set(CMAKE_C_COMPILER_ID, "Clang")
set(CMAKE_CXX_COMPILER_ID, "Clang")
# search for programs in the build host directories
set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
# for libraries and headers in the target directories
set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)

7
msg/ekf2_innovations.msg Normal file
View File

@ -0,0 +1,7 @@
uint64 timestamp # Timestamp in microseconds since boot
float32[6] vel_pos_innov # velocity and position innovations
float32[3] mag_innov # earth magnetic field innovations
float32 heading_innov # heading innovation
float32[6] vel_pos_innov_var # velocity and position innovation variances
float32[3] mag_innov_var # earth magnetic field innovation variance
float32 heading_innov_var # heading innovation variance

View File

@ -6,6 +6,12 @@ uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4
uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5
uint8 RC_INPUT_SOURCE_MAVLINK = 6
uint8 RC_INPUT_SOURCE_QURT = 7
uint8 RC_INPUT_SOURCE_PX4FMU_SPEKTRUM = 8
uint8 RC_INPUT_SOURCE_PX4FMU_SBUS = 9
uint8 RC_INPUT_SOURCE_PX4FMU_ST24 = 10
uint8 RC_INPUT_SOURCE_PX4FMU_SUMD = 11
uint8 RC_INPUT_SOURCE_PX4FMU_DSM = 12
uint8 RC_INPUT_SOURCE_PX4IO_SUMD = 13
uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels.
@ -14,7 +20,7 @@ uint64 timestamp_last_signal # last valid reception time
uint32 channel_count # number of channels actually being seen
int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception
bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly.
bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usUally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality.
uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality.
uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems

View File

@ -26,7 +26,7 @@ float32 z # throttle stick position 0..1
# in general the value corresponds to the demanded throttle by the user,
# if the input is used for setting the setpoint of a vertical position
# controller any value > 0.5 means up and any value < 0.5 means down
float32 r # yaw stick/twist positon, -1..1
float32 r # yaw stick/twist position, -1..1
# in general corresponds to the righthand rotation around the vertical
# (downwards) axis of the vehicle
float32 flaps # flap position
@ -38,8 +38,9 @@ float32 aux5 # default function: payload drop
uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE
uint8 rattitude_switch # rattitude control 2 position switch (optional): _MANUAL, RATTITUDE
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
uint8 kill_switch # throttle kill: _NORMAL_, KILL

View File

@ -1 +1,2 @@
uint64 timestamp # time at which the latest parameter was updated
bool saved # wether the change has already been saved to disk

View File

@ -1,4 +1,4 @@
int32 RC_CHANNELS_FUNCTION_MAX=20
int32 RC_CHANNELS_FUNCTION_MAX=21
uint8 RC_CHANNELS_FUNCTION_THROTTLE=0
uint8 RC_CHANNELS_FUNCTION_ROLL=1
uint8 RC_CHANNELS_FUNCTION_PITCH=2
@ -19,11 +19,12 @@ uint8 RC_CHANNELS_FUNCTION_PARAM_1=16
uint8 RC_CHANNELS_FUNCTION_PARAM_2=17
uint8 RC_CHANNELS_FUNCTION_PARAM_3_5=18
uint8 RC_CHANNELS_FUNCTION_RATTITUDE=19
uint8 RC_CHANNELS_FUNCTION_KILLSWITCH=20
uint64 timestamp # Timestamp in microseconds since boot time
uint64 timestamp_last_valid # Timestamp of last valid RC signal
float32[20] channels # Scaled to -1..1 (throttle: 0..1)
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
uint8 channel_count # Number of valid channels
int8[20] function # Functions mapping
int8[21] function # Functions mapping
uint8 rssi # Receive signal strength index
bool signal_lost # Control signal lost, should be checked together with topic timeout
uint32 frame_drop_count # Number of dropped frames

View File

@ -6,6 +6,6 @@ bool[3] valid #true for RC-Param channels which are mapped to a param
int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used
char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated
float32[3] scale # scale to map the RC input [-1, 1] to a parameter value
float32[3] value0 # inital value around which the parameter value is changed
float32[3] value0 # initial value around which the parameter value is changed
float32[3] value_min # minimal parameter value
float32[3] value_max # minimal parameter value

View File

@ -31,6 +31,7 @@ uint32 VEHICLE_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value. |S
uint32 VEHICLE_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty|
uint32 VEHICLE_CMD_DO_FLIGHTTERMINATION=185 # Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty|
uint32 VEHICLE_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
uint32 VEHICLE_CMD_DO_DIGICAM_CONTROL=203
uint32 VEHICLE_CMD_DO_MOUNT_CONFIGURE=204 # Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
uint32 VEHICLE_CMD_DO_MOUNT_CONTROL=205 # Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value|
uint32 VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206 # Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|

View File

@ -215,7 +215,7 @@
#define GPIO_UART4_RX GPIO_UART4_RX_1
#define GPIO_UART4_TX GPIO_UART4_TX_1
#define GPIO_USART6_RX GPIO_USART6_RX_1
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* RC_INPUT */
#define GPIO_USART6_TX GPIO_USART6_TX_1
#define GPIO_UART7_RX GPIO_UART7_RX_1
@ -257,9 +257,10 @@
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_1|GPIO_SPEED_50MHz)
/************************************************************************************
* Public Data

View File

@ -164,8 +164,8 @@ CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
CONFIG_USART1_TXBUFSIZE=64
CONFIG_USART2_TXBUFSIZE=64
CONFIG_USART1_TXBUFSIZE=32
CONFIG_USART2_TXBUFSIZE=32
CONFIG_USART3_TXBUFSIZE=64
CONFIG_USART1_RXBUFSIZE=64

View File

@ -0,0 +1,66 @@
uorb start
simulator start -s
param load
param set MAV_TYPE 20
param set MC_PITCHRATE_P 0.3
param set MC_ROLLRATE_P 0.3
param set MC_YAW_P 2.0
param set MC_YAWRATE_P 0.35
param set VT_TYPE 2
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
dataman start
param set CAL_GYRO0_ID 2293768
param set CAL_ACC0_ID 1376264
param set CAL_ACC1_ID 1310728
param set CAL_MAG0_ID 196616
param set CAL_GYRO0_XOFF 0.01
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_XOFF 0.01
param set CAL_MAG0_XOFF 0.01
param set MPC_XY_P 0.15
param set MPC_XY_VEL_P 0.05
param set MPC_XY_VEL_D 0.005
param set MPC_XY_FF 0.1
param set MPC_Z_VEL_MAX 1.0
param set SENS_BOARD_ROT 8
param set COM_RC_IN_MODE 1
rgbledsim start
tone_alarm start
gyrosim start
accelsim start
barosim start
adcsim start
gpssim start
measairspeedsim start
pwm_out_sim mode_pwm
sleep 1
sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
position_estimator_inav start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/standard_vtol_sitl.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink boot_complete
sdlog2 start -r 200 -e -t -a

View File

@ -27,6 +27,7 @@ param set MPC_XY_P 0.15
param set MPC_XY_VEL_P 0.05
param set MPC_XY_VEL_D 0.005
param set MPC_XY_FF 0.1
param set MPC_Z_VEL_MAX 1.0
param set SENS_BOARD_ROT 8
param set COM_RC_IN_MODE 1
rgbledsim start

View File

@ -51,8 +51,7 @@ sensors start
commander start
land_detector start multicopter
navigator start
attitude_estimator_q start
position_estimator_inav start
ekf2 start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix

View File

@ -3,8 +3,10 @@ simulator start -s
param load
param set MAV_TYPE 2
param set MC_PITCHRATE_P 0.15
param set MC_PITCH_P 7
param set MC_ROLL_P 7
param set MC_ROLLRATE_P 0.15
param set MC_YAW_P 2.0
param set MC_YAW_P 2.8
param set MC_YAWRATE_P 0.35
param set SYS_AUTOSTART 4010
param set SYS_RESTART_TYPE 2
@ -26,12 +28,22 @@ param set MPC_XY_P 0.4
param set MPC_XY_VEL_P 0.2
param set MPC_XY_VEL_D 0.005
param set SENS_BOARD_ROT 0
param set COM_RC_IN_MODE 1
param set NAV_ACC_RAD 2.0
param set RTL_RETURN_ALT 30.0
param set RTL_DESCEND_ALT 10.0
param set MIS_TAKEOFF_ALT 5.0
param set MPC_HOLD_MAX_Z 2.0
param set MPC_HOLD_XY_DZ 0.1
param set MPC_HOLD_Z_DZ 0.1
param set MPC_Z_VEL_MAX 2.0
param set MPC_Z_VEL_P 0.4
# changes for LPE
param set COM_RC_IN_MODE 1
param set LPE_BETA_MAX 10000
rgbled start
rgbledsim start
tone_alarm start
gyrosim start
accelsim start
@ -49,6 +61,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED_COV -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
@ -57,6 +70,7 @@ mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
mavlink stream -r 20 -s MANUAL_CONTROL -u 14556
mavlink boot_complete
sdlog2 start -r 100 -e -t -a

View File

View File

@ -115,6 +115,7 @@ __BEGIN_DECLS
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
#define PX4_SPI_BUS_EXT 4
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1

View File

@ -73,7 +73,7 @@ __BEGIN_DECLS
/* LEDs */
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11)
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3)
#define GPIO_LED_RED GPIO_LED1
@ -120,15 +120,24 @@ __BEGIN_DECLS
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
#define PX4_SPIDEV_HMC 5
#define PX4_SPIDEV_ICM 6
/* onboard MS5611 and FRAM are both on bus SPI2
* spi_dev_e:SPIDEV_FLASH has the value 2 and is used in the NuttX ramtron driver
* use 3 for the barometer to differentiate
*/
#define PX4_SPIDEV_BARO 3
#if (PX4_SPIDEV_BARO == SPIDEV_FLASH)
#error PX4_SPIDEV_BARO must not be equal to SPIDEV_FLASH as they share the same bus
#endif
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
@ -145,13 +154,12 @@ __BEGIN_DECLS
*
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
*/
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15)
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* User GPIOs
*
@ -215,7 +223,7 @@ __BEGIN_DECLS
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 2 */
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
#define SBUS_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_PORT "/dev/ttyS4"
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
@ -226,7 +234,12 @@ __BEGIN_DECLS
#define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN3)
#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
/* for R07, this signal is active low */
//#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
//#define INVERT_RC_INPUT(_s) stm32_gpiowrite(GPIO_SBUS_INV, 1-_s);
/* for R12, this signal is active high */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define INVERT_RC_INPUT(_s) stm32_gpiowrite(GPIO_SBUS_INV, _s);
#define GPIO_8266_GPIO0 (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN2)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -235,11 +248,14 @@ __BEGIN_DECLS
/* Power switch controls ******************************************************/
#define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s))
#define GPIO_USART1_RX_SPEKTRUM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_HIGH(_s) stm32_gpiowrite(GPIO_USART1_RX_SPEKTRUM, (_s))
#define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (1-_s))
//#define GPIO_USART1_RX_SPEKTRUM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_UART() stm32_configgpio(GPIO_USART1_RX)
#define SPEKTRUM_RX_AS_GPIO() stm32_configgpio(GPIO_USART1_RX_SPEKTRUM)
// FMUv4 has a separate GPIO for serial RC output
#define GPIO_RC_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN6)
#define SPEKTRUM_RX_AS_GPIO() stm32_configgpio(GPIO_RC_OUT)
#define SPEKTRUM_RX_HIGH(_s) stm32_gpiowrite(GPIO_RC_OUT, (_s))
/****************************************************************************************************
* Public Types

View File

@ -219,10 +219,6 @@ __EXPORT int nsh_archinitialize(void)
stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
stm32_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
stm32_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
stm32_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
/* configure power supply control/sense pins */
stm32_configgpio(GPIO_PERIPH_3V3_EN);
stm32_configgpio(GPIO_VDD_BRICK_VALID);
@ -233,6 +229,10 @@ __EXPORT int nsh_archinitialize(void)
stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
stm32_configgpio(GPIO_8266_PD);
stm32_configgpio(GPIO_8266_RST);
#ifdef GPIO_RC_OUT
stm32_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
stm32_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
#endif
/* configure the high-resolution time/callout interface */
hrt_init();
@ -284,7 +284,6 @@ __EXPORT int nsh_archinitialize(void)
SPI_SETMODE(spi1, SPIDEV_MODE3);
SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
SPI_SELECT(spi1, PX4_SPIDEV_HMC, false);
SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
up_udelay(20);
@ -298,14 +297,16 @@ __EXPORT int nsh_archinitialize(void)
return -ENODEV;
}
/* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max)
* and de-assert the known chip selects. */
/* Default SPI2 to 12MHz and de-assert the known chip selects.
* MS5611 has max SPI clock speed of 20MHz
*/
// XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated
SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000);
// XXX start with 10.4 MHz and go up to 20 once validated
SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000);
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);
SPI_SELECT(spi2, SPIDEV_FLASH, false);
SPI_SELECT(spi2, PX4_SPIDEV_BARO, false);
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */

View File

@ -70,36 +70,36 @@ __EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
.gpio = GPIO_TIM1_CH4OUT,
.timer_index = 0,
.timer_channel = 4,
.default_value = 1000,
.default_value = 900,
},
{
.gpio = GPIO_TIM1_CH3OUT,
.timer_index = 0,
.timer_channel = 3,
.default_value = 1000,
.default_value = 900,
},
{
.gpio = GPIO_TIM1_CH2OUT,
.timer_index = 0,
.timer_channel = 2,
.default_value = 1000,
.default_value = 900,
},
{
.gpio = GPIO_TIM1_CH1OUT,
.timer_index = 0,
.timer_channel = 1,
.default_value = 1000,
.default_value = 900,
},
{
.gpio = GPIO_TIM4_CH2OUT,
.timer_index = 1,
.timer_channel = 2,
.default_value = 1000,
.default_value = 900,
},
{
.gpio = GPIO_TIM4_CH3OUT,
.timer_index = 1,
.timer_channel = 3,
.default_value = 1000,
.default_value = 900,
}
};

View File

@ -151,8 +151,24 @@ __EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
#ifdef CONFIG_STM32_SPI2
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* there can only be one device on this bus, so always select it */
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
/* SPI select is active low, so write !selected to select the device */
switch (devid) {
case SPIDEV_FLASH:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
break;
case PX4_SPIDEV_BARO:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
stm32_gpiowrite(GPIO_SPI_CS_MS5611, !selected);
break;
default:
break;
}
}
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)

View File

@ -34,7 +34,7 @@
/**
* @file camera_trigger.cpp
*
* External camera-IMU synchronisation and triggering via FMU auxillary pins.
* External camera-IMU synchronisation and triggering via FMU auxiliary pins.
*
* @author Mohammed Kabir <mhkabir98@gmail.com>
*/

View File

@ -79,6 +79,8 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f);
*
* 0 disables the trigger, 1 sets it to enabled on command, 2 always on
*
* @reboot_required true
*
* @min 0
* @max 2
* @group Camera trigger

View File

@ -77,6 +77,15 @@ protected:
int irq = 0);
virtual ~SPI();
/**
* Locking modes supported by the driver.
*/
enum LockMode {
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
};
virtual int init();
/**
@ -117,13 +126,14 @@ protected:
void set_frequency(uint32_t frequency);
/**
* Locking modes supported by the driver.
* Set the SPI bus locking mode
*
* This set the SPI locking mode. For devices competing with NuttX SPI
* drivers on a bus the right lock mode is LOCK_THREADS.
*
* @param mode Locking mode
*/
enum LockMode {
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
};
void set_lockmode(enum LockMode mode) { locking_mode = mode; }
LockMode locking_mode; /**< selected locking mode */

View File

@ -38,6 +38,7 @@ px4_add_module(
-Os
SRCS
frsky_data.c
sPort_data.c
frsky_telemetry.c
DEPENDS
platforms__common

View File

@ -35,11 +35,13 @@
/**
* @file frsky_telemetry.c
* @author Stefan Rado <px4@sradonia.net>
* @author Mark Whitehorn <kd0aij@github.com>
*
* FrSky telemetry implementation.
* FrSky D8 mode and SmartPort (D16 mode) telemetry implementation.
*
* This daemon emulates an FrSky sensor hub by periodically sending data
* packets to an attached FrSky receiver.
* This daemon emulates the FrSky Sensor Hub for D8 mode.
* For X series receivers (D16 mode) it emulates SmartPort sensors by responding to polling
* packets received from an attached FrSky X series receiver.
*
*/
@ -48,12 +50,15 @@
#include <stdbool.h>
#include <string.h>
#include <sys/types.h>
#include <poll.h>
#include <fcntl.h>
#include <unistd.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
#include <termios.h>
#include <drivers/drv_hrt.h>
#include "sPort_data.h"
#include "frsky_data.h"
@ -63,7 +68,8 @@ static volatile bool thread_running = false;
static int frsky_task;
/* functions */
static int frsky_open_uart(const char *uart_name, struct termios *uart_config_original);
static int sPort_open_uart(const char *uart_name, struct termios *uart_config, struct termios *uart_config_original);
static int set_uart_speed(int uart, struct termios *uart_config, speed_t speed);
static void usage(void);
static int frsky_telemetry_thread_main(int argc, char *argv[]);
__EXPORT int frsky_telemetry_main(int argc, char *argv[]);
@ -72,10 +78,10 @@ __EXPORT int frsky_telemetry_main(int argc, char *argv[]);
/**
* Opens the UART device and sets all required serial parameters.
*/
static int frsky_open_uart(const char *uart_name, struct termios *uart_config_original)
static int sPort_open_uart(const char *uart_name, struct termios *uart_config, struct termios *uart_config_original)
{
/* Open UART */
const int uart = open(uart_name, O_WRONLY | O_NOCTTY);
const int uart = open(uart_name, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (uart < 0) {
err(1, "Error opening port: %s", uart_name);
@ -91,22 +97,21 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or
}
/* Fill the struct for the new configuration */
struct termios uart_config;
tcgetattr(uart, &uart_config);
tcgetattr(uart, uart_config);
/* Disable output post-processing */
uart_config.c_oflag &= ~OPOST;
uart_config->c_oflag &= ~OPOST;
/* Set baud rate */
static const speed_t speed = B9600;
static const speed_t speed = B57600;
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
if (cfsetispeed(uart_config, speed) < 0 || cfsetospeed(uart_config, speed) < 0) {
warnx("ERR: %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
if ((termios_state = tcsetattr(uart, TCSANOW, uart_config)) < 0) {
warnx("ERR: %s (tcsetattr)\n", uart_name);
close(uart);
return -1;
@ -115,6 +120,20 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or
return uart;
}
static int set_uart_speed(int uart, struct termios *uart_config, speed_t speed)
{
if (cfsetispeed(uart_config, speed) < 0) {
return -1;
}
if (tcsetattr(uart, TCSANOW, uart_config) < 0) {
return -1;
}
return uart;
}
/**
* Print command usage information
*/
@ -133,7 +152,7 @@ static void usage()
static int frsky_telemetry_thread_main(int argc, char *argv[])
{
/* Default values for arguments */
char *device_name = "/dev/ttyS1"; /* USART2 */
char *device_name = "/dev/ttyS6"; /* USART8 */
/* Work around some stupidity in task_create's argv handling */
argc -= 2;
@ -154,42 +173,181 @@ static int frsky_telemetry_thread_main(int argc, char *argv[])
}
/* Open UART */
warnx("opening uart");
struct termios uart_config_original;
const int uart = frsky_open_uart(device_name, &uart_config_original);
struct termios uart_config;
const int uart = sPort_open_uart(device_name, &uart_config, &uart_config_original);
if (uart < 0) {
warnx("could not open %s", device_name);
err(1, "could not open %s", device_name);
}
/* Subscribe to topics */
frsky_init();
/* poll descriptor */
struct pollfd fds[1];
fds[0].fd = uart;
fds[0].events = POLLIN;
thread_running = true;
/* Main thread loop */
unsigned int iteration = 0;
char sbuf[20];
while (!thread_should_exit) {
/* look for polling bytes indicating SmartPort telemetry
* if not found, send D type telemetry frames instead
*/
int status = poll(fds, sizeof(fds) / sizeof(fds[0]), 3000);
/* Sleep 200 ms */
usleep(200000);
if (status > 0) {
/* traffic on the port, assume it's a SmartPort master */
/* Subscribe to topics */
sPort_init();
/* Send frame 1 (every 200ms): acceleration values, altitude (vario), temperatures, current & voltages, RPM */
frsky_send_frame1(uart);
/* send S.port telemetry */
while (!thread_should_exit) {
/* Send frame 2 (every 1000ms): course, latitude, longitude, speed, altitude (GPS), fuel level */
if (iteration % 5 == 0) {
frsky_send_frame2(uart);
/* wait for poll frame starting with value 0x7E
* note that only the bus master is supposed to put a 0x7E on the bus.
* slaves use byte stuffing to send 0x7E and 0x7D.
* we expect a poll frame every 12msec
*/
int status = poll(fds, sizeof(fds) / sizeof(fds[0]), 50);
if (status < 1) { continue; }
// read 1 byte
int newBytes = read(uart, &sbuf[0], 1);
if (newBytes < 1 || sbuf[0] != 0x7E) { continue; }
/* wait for ID byte */
status = poll(fds, sizeof(fds) / sizeof(fds[0]), 50);
if (status < 1) { continue; }
hrt_abstime now = hrt_absolute_time();
newBytes = read(uart, &sbuf[1], 1);
// allow a minimum of 500usec before reply
usleep(500);
static hrt_abstime lastBATV = 0;
static hrt_abstime lastCUR = 0;
static hrt_abstime lastALT = 0;
static hrt_abstime lastSPD = 0;
static hrt_abstime lastFUEL = 0;
switch (sbuf[1]) {
case SMARTPORT_POLL_1:
/* report BATV at 1Hz */
if (now - lastBATV > 1000 * 1000) {
lastBATV = now;
/* send battery voltage */
sPort_send_BATV(uart);
}
break;
case SMARTPORT_POLL_2:
/* report battery current at 5Hz */
if (now - lastCUR > 200 * 1000) {
lastCUR = now;
/* send battery current */
sPort_send_CUR(uart);
}
break;
case SMARTPORT_POLL_3:
/* report altitude at 5Hz */
if (now - lastALT > 200 * 1000) {
lastALT = now;
/* send altitude */
sPort_send_ALT(uart);
}
break;
case SMARTPORT_POLL_4:
/* report speed at 5Hz */
if (now - lastSPD > 200 * 1000) {
lastSPD = now;
/* send speed */
sPort_send_SPD(uart);
}
break;
case SMARTPORT_POLL_5:
/* report fuel at 1Hz */
if (now - lastFUEL > 1000 * 1000) {
lastFUEL = now;
/* send fuel */
sPort_send_FUEL(uart);
}
break;
}
}
/* Send frame 3 (every 5000ms): date, time */
if (iteration % 25 == 0) {
frsky_send_frame3(uart);
} else {
iteration = 0;
/* timed out: reconfigure UART and send D type telemetry */
warnx("SmartPort receiver not detected, sending FrSky D type telemetry");
status = set_uart_speed(uart, &uart_config, B9600);
if (status < 0) {
warnx("error setting speed for %s, quitting", device_name);
/* Reset the UART flags to original state */
tcsetattr(uart, TCSANOW, &uart_config_original);
close(uart);
thread_running = false;
return 0;
}
iteration++;
int iteration = 0;
/* Subscribe to topics */
frsky_init();
/* send D8 mode telemetry */
while (!thread_should_exit) {
/* Sleep 200 ms */
usleep(200000);
/* Send frame 1 (every 200ms): acceleration values, altitude (vario), temperatures, current & voltages, RPM */
frsky_send_frame1(uart);
/* Send frame 2 (every 1000ms): course, latitude, longitude, speed, altitude (GPS), fuel level */
if (iteration % 5 == 0) {
frsky_send_frame2(uart);
}
/* Send frame 3 (every 5000ms): date, time */
if (iteration % 25 == 0) {
frsky_send_frame3(uart);
iteration = 0;
}
iteration++;
}
/* TODO: flush the input buffer if in full duplex mode */
read(uart, &sbuf[0], sizeof(sbuf));
}
/* Reset the UART flags to original state */
@ -221,7 +379,7 @@ int frsky_telemetry_main(int argc, char *argv[])
thread_should_exit = false;
frsky_task = px4_task_spawn_cmd("frsky_telemetry",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
200,
2000,
frsky_telemetry_thread_main,
(char *const *)argv);

View File

@ -0,0 +1,217 @@
/****************************************************************************
*
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
* Author: Stefan Rado <px4@sradonia.net>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file sPort_data.c
* @author Stefan Rado <px4@sradonia.net>
* @author Mark Whitehorn <kd0aij@github.com>
*
* FrSky SmartPort telemetry implementation.
*
*/
#include "sPort_data.h"
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <arch/math.h>
#include <geo/geo.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_status.h>
#include <drivers/drv_hrt.h>
#define frac(f) (f - (int)f)
static int battery_sub = -1;
static int sensor_sub = -1;
static int global_position_sub = -1;
static int vehicle_status_sub = -1;
/**
* Initializes the uORB subscriptions.
*/
void sPort_init()
{
battery_sub = orb_subscribe(ORB_ID(battery_status));
global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
}
/**
* Sends a 0x10 start byte.
*/
//static void sPort_send_start(int uart)
//{
// static const uint8_t c = 0x10;
// write(uart, &c, 1);
//}
static void update_crc(uint16_t *crc, unsigned char b)
{
*crc += b;
*crc += *crc >> 8;
*crc &= 0xFF;
}
/**
* Sends one byte, performing byte-stuffing if necessary.
*/
static void sPort_send_byte(int uart, uint8_t value)
{
const uint8_t x7E[] = { 0x7D, 0x5E };
const uint8_t x7D[] = { 0x7D, 0x5D };
switch (value) {
case 0x7E:
write(uart, x7E, sizeof(x7E));
break;
case 0x7D:
write(uart, x7D, sizeof(x7D));
break;
default:
write(uart, &value, sizeof(value));
break;
}
}
/**
* Sends one data id/value pair.
*/
void sPort_send_data(int uart, uint16_t id, uint32_t data)
{
union {
uint32_t word;
uint8_t byte[4];
} buf;
/* send start byte */
static const uint8_t c = 0x10;
write(uart, &c, 1);
/* init crc */
uint16_t crc = c;
buf.word = id;
for (int i = 0; i < 2; i++) {
update_crc(&crc, buf.byte[i]);
sPort_send_byte(uart, buf.byte[i]); /* LSB first */
}
buf.word = data;
for (int i = 0; i < 4; i++) {
update_crc(&crc, buf.byte[i]);
sPort_send_byte(uart, buf.byte[i]); /* LSB first */
}
sPort_send_byte(uart, 0xFF - crc);
}
// scaling correct with OpenTX 2.1.7
void sPort_send_BATV(int uart)
{
/* get a local copy of the vehicle status data */
struct vehicle_status_s vehicle_status;
memset(&vehicle_status, 0, sizeof(vehicle_status));
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vehicle_status);
/* send battery voltage as VFAS */
uint32_t voltage = (int)(100 * vehicle_status.battery_voltage);
sPort_send_data(uart, SMARTPORT_ID_VFAS, voltage);
}
// verified scaling
void sPort_send_CUR(int uart)
{
/* get a local copy of the vehicle status data */
struct vehicle_status_s vehicle_status;
memset(&vehicle_status, 0, sizeof(vehicle_status));
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vehicle_status);
/* send data */
uint32_t current = (int)(10 * vehicle_status.battery_current);
sPort_send_data(uart, SMARTPORT_ID_CURR, current);
}
// verified scaling for "custom" altitude option
// OpenTX uses the initial reading as field elevation and displays
// the difference (altitude - field)
void sPort_send_ALT(int uart)
{
/* get a local copy of the current sensor values */
struct sensor_combined_s raw;
memset(&raw, 0, sizeof(raw));
orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
/* send data */
uint32_t alt = (int)(100 * raw.baro_alt_meter[0]);
sPort_send_data(uart, SMARTPORT_ID_ALT, alt);
}
// verified scaling for "calculated" option
void sPort_send_SPD(int uart)
{
/* get a local copy of the global position data */
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_pos);
/* send data for A2 */
float speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e);
uint32_t ispeed = (int)(10 * speed);
sPort_send_data(uart, SMARTPORT_ID_GPS_SPD, ispeed);
}
// verified scaling
void sPort_send_FUEL(int uart)
{
/* get a local copy of the vehicle status data */
struct vehicle_status_s vehicle_status;
memset(&vehicle_status, 0, sizeof(vehicle_status));
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vehicle_status);
/* send data */
uint32_t fuel = (int)(100 * vehicle_status.battery_remaining);
sPort_send_data(uart, SMARTPORT_ID_FUEL, fuel);
}

View File

@ -0,0 +1,87 @@
/****************************************************************************
*
* Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
* Author: Stefan Rado <px4@sradonia.net>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file sPort_data.h
* @author Mark Whitehorn <kd0aij@github.com>
*
* FrSky SmartPort telemetry implementation.
*
*/
#ifndef _SPORT_DATA_H
#define _SPORT_DATA_H
#include <sys/types.h>
/* FrSky SmartPort polling IDs captured from X4R */
#define SMARTPORT_POLL_1 0x1B
#define SMARTPORT_POLL_2 0x34
#define SMARTPORT_POLL_3 0x95
#define SMARTPORT_POLL_4 0x16
#define SMARTPORT_POLL_5 0xB7
/* FrSky SmartPort sensor IDs */
#define SMARTPORT_ID_RSSI 0xf101
#define SMARTPORT_ID_RXA1 0xf102 // supplied by RX
#define SMARTPORT_ID_RXA2 0xf103 // supplied by RX
#define SMARTPORT_ID_BATV 0xf104
#define SMARTPORT_ID_SWR 0xf105
#define SMARTPORT_ID_T1 0x0400
#define SMARTPORT_ID_T2 0x0410
#define SMARTPORT_ID_RPM 0x0500
#define SMARTPORT_ID_FUEL 0x0600
#define SMARTPORT_ID_ALT 0x0100
#define SMARTPORT_ID_VARIO 0x0110
#define SMARTPORT_ID_ACCX 0x0700
#define SMARTPORT_ID_ACCY 0x0710
#define SMARTPORT_ID_ACCZ 0x0720
#define SMARTPORT_ID_CURR 0x0200
#define SMARTPORT_ID_VFAS 0x0210
#define SMARTPORT_ID_CELLS 0x0300
#define SMARTPORT_ID_GPS_LON_LAT 0x0800
#define SMARTPORT_ID_GPS_ALT 0x0820
#define SMARTPORT_ID_GPS_SPD 0x0830
#define SMARTPORT_ID_GPS_CRS 0x0840
#define SMARTPORT_ID_GPS_TIME 0x0850
// Public functions
void sPort_init(void);
void sPort_send_data(int uart, uint16_t id, uint32_t data);
void sPort_send_BATV(int uart);
void sPort_send_CUR(int uart);
void sPort_send_ALT(int uart);
void sPort_send_SPD(int uart);
void sPort_send_FUEL(int uart);
#endif /* _SPORT_TELEMETRY_H */

View File

@ -55,11 +55,11 @@
PARAM_DEFINE_INT32(GMB_USE_MNT, 0);
/**
* Auxilary switch to set mount operation mode.
* Auxiliary switch to set mount operation mode.
*
* Set to 0 to disable manual mode control.
*
* If set to an auxilary switch:
* If set to an auxiliary switch:
* Switch off means the gimbal is put into safe/locked position.
* Switch on means the gimbal can move freely, and landing gear
* will be retracted if applicable.

View File

@ -402,7 +402,12 @@ GPS::task_main()
if (!(_pub_blocked)) {
if (helper_ret & 1) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
if (_report_gps_pos_pub != nullptr) {
orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
_report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
if (_p_report_sat_info && (helper_ret & 2)) {

View File

@ -72,7 +72,7 @@ typedef struct {
uint32_t msl_altitude; ///< MSL altitude in meters * 10^2
uint32_t ground_speed; ///< velocity in m/s
int32_t heading; ///< heading in degrees * 10^2
uint8_t satellites; ///< number of sattelites used
uint8_t satellites; ///< number of satellites used
uint8_t fix_type; ///< fix type: XXX correct for that
uint32_t date;
uint32_t utc_time;

View File

@ -44,8 +44,8 @@
* @author Hannes Delago
* (rework, add ubx7+ compatibility)
*
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8_ReceiverDescriptionProtocolSpec_%28UBX-13003221%29_Public.pdf
* @see https://www2.u-blox.com/images/downloads/Product_Docs/u-blox6-GPS-GLONASS-QZSS-V14_ReceiverDescriptionProtocolSpec_Public_(GPS.G6-SW-12013).pdf
* @see https://www.u-blox.com/sites/default/files/products/documents/u-bloxM8_ReceiverDescrProtSpec_%28UBX-13003221%29_Public.pdf
*/
#include <assert.h>

View File

@ -182,7 +182,7 @@ hott_sensors_thread_main(int argc, char *argv[])
recv_data(uart, &buffer[0], &size, &id);
// Determine which moduel sent it and process accordingly.
// Determine which module sent it and process accordingly.
if (id == GAM_SENSOR_ID) {
publish_gam_message(buffer);

View File

@ -291,7 +291,7 @@ build_gps_response(uint8_t *buffer, size_t *size)
msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
/* Get any (and probably only ever one) _home_sub postion report */
/* Get any (and probably only ever one) _home_sub position report */
bool updated;
orb_check(_home_sub, &updated);

View File

@ -211,7 +211,7 @@ struct gps_module_msg {
uint8_t resolution_L; /**< 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */
uint8_t resolution_H; /**< 117 = High Byte m/s resolution 0.01m */
uint8_t unknown1; /**< 120 = 0m/3s */
uint8_t gps_num_sat; /**< GPS.Satellites (number of satelites) (1 byte) */
uint8_t gps_num_sat; /**< GPS.Satellites (number of satellites) (1 byte) */
uint8_t gps_fix_char; /**< GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */
uint8_t home_direction; /**< HomeDirection (direction from starting point to Model position) (1 byte) */
uint8_t angle_x_direction; /**< angle x-direction (1 byte) */

View File

@ -265,7 +265,7 @@ MS5611_I2C::_read_prom()
/* check if all bytes are zero */
if (i == 0) {
/* initalize to first byte read */
/* initialize to first byte read */
last_val = prom_buf[0];
}

View File

@ -829,7 +829,7 @@ struct ms5611_bus_option {
{ MS5611_BUS_SPI_EXTERNAL, "/dev/ms5611_spi_ext", &MS5611_spi_interface, PX4_SPI_BUS_EXT, NULL },
#endif
#ifdef PX4_SPIDEV_BARO
{ MS5611_BUS_SPI_INTERNAL, "/dev/ms5611_spi_int", &MS5611_spi_interface, PX4_SPI_BUS_SENSORS, NULL },
{ MS5611_BUS_SPI_INTERNAL, "/dev/ms5611_spi_int", &MS5611_spi_interface, PX4_SPI_BUS_BARO, NULL },
#endif
#ifdef PX4_I2C_BUS_ONBOARD
{ MS5611_BUS_I2C_INTERNAL, "/dev/ms5611_int", &MS5611_i2c_interface, PX4_I2C_BUS_ONBOARD, NULL },

View File

@ -131,7 +131,7 @@ MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
}
MS5611_SPI::MS5611_SPI(uint8_t bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 11 * 1000 * 1000 /* will be rounded to 10.4 MHz */),
SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 20 * 1000 * 1000 /* will be rounded to 10.4 MHz */),
_prom(prom_buf)
{
}
@ -152,6 +152,11 @@ MS5611_SPI::init()
goto out;
}
/* sharing a bus with NuttX drivers */
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
//set_lockmode(SPI::LOCK_THREADS);
#endif
/* send reset command */
ret = _reset();

View File

@ -536,7 +536,7 @@ void PWMIN::print_info(void)
/*
* Handle the interupt, gathering pulse data
* Handle the interrupt, gathering pulse data
*/
static int pwmin_tim_isr(int irq, void *context)
{

View File

@ -502,8 +502,8 @@ PWMSim::task_main()
PX4_ISFINITE(outputs.output[i]) &&
outputs.output[i] >= -1.0f &&
outputs.output[i] <= 1.0f) {
/* scale for PWM output 900 - 2100us */
outputs.output[i] = 1500 + (600 * outputs.output[i]);
/* scale for PWM output 1000 - 2000us */
outputs.output[i] = 1500 + (500 * outputs.output[i]);
} else {
/*

View File

@ -119,6 +119,27 @@ public:
int set_i2c_bus_clock(unsigned bus, unsigned clock_hz);
private:
enum RC_SCAN {
RC_SCAN_PPM = 0,
RC_SCAN_SBUS,
RC_SCAN_DSM,
RC_SCAN_SUMD,
RC_SCAN_ST24
};
enum RC_SCAN _rc_scan_state = RC_SCAN_SBUS;
char const *RC_SCAN_STRING[5] = {
"PPM",
"SBUS",
"DSM",
"SUMD",
"ST24"
};
hrt_abstime _rc_scan_begin = 0;
bool _rc_scan_locked = false;
bool _report_lock = true;
static const unsigned _max_actuators = DIRECT_PWM_OUTPUT_CHANNELS;
Mode _mode;
@ -134,12 +155,14 @@ private:
orb_advert_t _outputs_pub;
unsigned _num_outputs;
int _class_instance;
int _sbus_fd;
int _dsm_fd;
int _rcs_fd;
uint8_t _rcs_buf[SBUS_FRAME_SIZE];
volatile bool _initialized;
bool _throttle_armed;
bool _pwm_on;
bool _pwm_init;
uint8_t _pwm_channel_mask;
MixerGroup *_mixers;
@ -199,6 +222,14 @@ private:
/* do not allow to copy due to ptr data members */
PX4FMU(const PX4FMU &);
PX4FMU operator=(const PX4FMU &);
void fill_rc_in(uint16_t raw_rc_count,
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe,
unsigned frame_drops, int rssi);
void dsm_bind_ioctl(int dsmMode);
void set_rc_scan_state(RC_SCAN _rc_scan_state);
void rc_io_invert();
void rc_io_invert(bool invert);
};
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
@ -280,11 +311,12 @@ PX4FMU::PX4FMU() :
_outputs_pub(nullptr),
_num_outputs(0),
_class_instance(0),
_sbus_fd(-1),
_dsm_fd(-1),
_rcs_fd(-1),
_initialized(false),
_throttle_armed(false),
_pwm_on(false),
_pwm_init(false),
_pwm_channel_mask(0),
_mixers(nullptr),
_groups_required(0),
_groups_subscribed(0),
@ -390,10 +422,7 @@ PX4FMU::set_mode(Mode mode)
_pwm_default_rate = 50;
_pwm_alt_rate = 50;
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
up_pwm_servo_init(0x3);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
_pwm_channel_mask = 0x3;
break;
@ -404,10 +433,7 @@ PX4FMU::set_mode(Mode mode)
_pwm_default_rate = 50;
_pwm_alt_rate = 50;
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
up_pwm_servo_init(0xf);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
_pwm_channel_mask = 0xf;
break;
@ -418,10 +444,7 @@ PX4FMU::set_mode(Mode mode)
_pwm_default_rate = 50;
_pwm_alt_rate = 50;
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
up_pwm_servo_init(0x3f);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
_pwm_channel_mask = 0x3f;
break;
@ -433,10 +456,7 @@ PX4FMU::set_mode(Mode mode)
_pwm_default_rate = 50;
_pwm_alt_rate = 50;
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
up_pwm_servo_init(0xff);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
_pwm_channel_mask = 0xff;
break;
#endif
@ -449,6 +469,7 @@ PX4FMU::set_mode(Mode mode)
/* disable servo outputs - no need to set rates */
up_pwm_servo_deinit();
_pwm_init = false;
break;
@ -613,6 +634,56 @@ PX4FMU::cycle_trampoline(void *arg)
dev->cycle();
}
void PX4FMU::fill_rc_in(uint16_t raw_rc_count,
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe,
unsigned frame_drops, int rssi = -1)
{
// fill rc_in struct for publishing
_rc_in.channel_count = raw_rc_count;
if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
_rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
for (uint8_t i = 0; i < _rc_in.channel_count; i++) {
_rc_in.values[i] = raw_rc_values[i];
}
_rc_in.timestamp_publication = now;
_rc_in.timestamp_last_signal = _rc_in.timestamp_publication;
_rc_in.rc_ppm_frame_length = 0;
if (rssi == -1) {
_rc_in.rssi =
(!frame_drop) ? RC_INPUT_RSSI_MAX : (RC_INPUT_RSSI_MAX / 2);
}
_rc_in.rc_failsafe = failsafe;
_rc_in.rc_lost = false;
_rc_in.rc_lost_frame_count = frame_drops;
_rc_in.rc_total_frame_count = 0;
}
#ifdef RC_SERIAL_PORT
void PX4FMU::set_rc_scan_state(RC_SCAN newState)
{
// warnx("RCscan: %s failed, trying %s", PX4FMU::RC_SCAN_STRING[_rc_scan_state], PX4FMU::RC_SCAN_STRING[newState]);
_rc_scan_begin = 0;
_rc_scan_state = newState;
}
void PX4FMU::rc_io_invert(bool invert)
{
INVERT_RC_INPUT(invert);
if (!invert) {
// set FMU_RC_OUTPUT high to pull RC_INPUT up
stm32_gpiowrite(GPIO_RC_OUT, 1);
}
}
#endif
void
PX4FMU::cycle()
{
@ -631,19 +702,18 @@ PX4FMU::cycle()
update_pwm_rev_mask();
#ifdef SBUS_SERIAL_PORT
_sbus_fd = sbus_init(SBUS_SERIAL_PORT, false);
#endif
#ifdef DSM_SERIAL_PORT
// XXX rather than opening it we need to cycle between protocols until one is locked in
//_dsm_fd = dsm_init(DSM_SERIAL_PORT);
#ifdef RC_SERIAL_PORT
// dsm_init sets some file static variables and returns a file descriptor
_rcs_fd = dsm_init(RC_SERIAL_PORT);
// assume SBUS input
sbus_config(_rcs_fd, false);
// disable CPPM input by mapping it away from the timer capture input
stm32_configgpio(GPIO_PPM_IN & ~(GPIO_AF_MASK | GPIO_PUPD_MASK));
#endif
_initialized = true;
}
if (_groups_subscribed != _groups_required) {
subscribe();
_groups_subscribed = _groups_required;
@ -796,6 +866,13 @@ PX4FMU::cycle()
if (_pwm_on != pwm_on) {
_pwm_on = pwm_on;
if (!_pwm_init && _pwm_on) {
up_pwm_servo_init(_pwm_channel_mask);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
_pwm_init = true;
}
up_pwm_servo_arm(pwm_on);
}
}
@ -807,74 +884,237 @@ PX4FMU::cycle()
orb_copy(ORB_ID(parameter_update), _param_sub, &pupdate);
update_pwm_rev_mask();
int32_t dsm_bind_val;
param_t dsm_bind_param;
/* see if bind parameter has been set, and reset it to -1 */
param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
if (dsm_bind_val > -1) {
dsm_bind_ioctl(dsm_bind_val);
dsm_bind_val = -1;
param_set(dsm_bind_param, &dsm_bind_val);
}
}
bool rc_updated = false;
#ifdef SBUS_SERIAL_PORT
#ifdef RC_SERIAL_PORT
// This block scans for a supported serial RC input and locks onto the first one found
// Scan for 100 msec, then switch protocol
constexpr hrt_abstime rc_scan_max = 100 * 1000;
bool sbus_failsafe, sbus_frame_drop;
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS];
uint16_t raw_rc_count;
bool sbus_updated = sbus_input(_sbus_fd, &raw_rc_values[0], &raw_rc_count, &sbus_failsafe, &sbus_frame_drop,
input_rc_s::RC_INPUT_MAX_CHANNELS);
unsigned frame_drops;
bool dsm_11_bit;
if (sbus_updated) {
// we have a new PPM frame. Publish it.
_rc_in.channel_count = raw_rc_count;
if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
_rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
for (uint8_t i = 0; i < _rc_in.channel_count; i++) {
_rc_in.values[i] = raw_rc_values[i];
}
_rc_in.timestamp_publication = hrt_absolute_time();
_rc_in.timestamp_last_signal = _rc_in.timestamp_publication;
_rc_in.rc_ppm_frame_length = 0;
_rc_in.rssi = (!sbus_frame_drop) ? RC_INPUT_RSSI_MAX : (RC_INPUT_RSSI_MAX / 2);
_rc_in.rc_failsafe = sbus_failsafe;
_rc_in.rc_lost = false;
_rc_in.rc_lost_frame_count = sbus_dropped_frames();
_rc_in.rc_total_frame_count = 0;
rc_updated = true;
if (_report_lock && _rc_scan_locked) {
_report_lock = false;
warnx("RCscan: %s RC input locked", RC_SCAN_STRING[_rc_scan_state]);
}
#endif
// read all available data from the serial RC input UART
hrt_abstime now = hrt_absolute_time();
int newBytes = ::read(_rcs_fd, &_rcs_buf[0], SBUS_FRAME_SIZE);
switch (_rc_scan_state) {
case RC_SCAN_SBUS:
if (_rc_scan_begin == 0) {
_rc_scan_begin = now;
// Configure serial port for SBUS
sbus_config(_rcs_fd, false);
rc_io_invert(true);
} else if (_rc_scan_locked
|| now - _rc_scan_begin < rc_scan_max) {
// parse new data
if (newBytes > 0) {
rc_updated = sbus_parse(now, &_rcs_buf[0], newBytes, &raw_rc_values[0], &raw_rc_count, &sbus_failsafe,
&sbus_frame_drop, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
// we have a new SBUS frame. Publish it.
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS;
fill_rc_in(raw_rc_count, raw_rc_values, now,
sbus_frame_drop, sbus_failsafe, frame_drops);
_rc_scan_locked = true;
}
}
} else {
// Scan the next protocol
set_rc_scan_state(RC_SCAN_DSM);
}
break;
case RC_SCAN_DSM:
if (_rc_scan_begin == 0) {
_rc_scan_begin = now;
// // Configure serial port for DSM
dsm_config(_rcs_fd);
rc_io_invert(false);
} else if (_rc_scan_locked
|| now - _rc_scan_begin < rc_scan_max) {
if (newBytes > 0) {
// parse new data
rc_updated = dsm_parse(now, &_rcs_buf[0], newBytes, &raw_rc_values[0], &raw_rc_count,
&dsm_11_bit, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
// we have a new DSM frame. Publish it.
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM;
fill_rc_in(raw_rc_count, raw_rc_values, now,
false, false, frame_drops);
_rc_scan_locked = true;
}
}
} else {
// Scan the next protocol
set_rc_scan_state(RC_SCAN_ST24);
}
break;
case RC_SCAN_ST24:
if (_rc_scan_begin == 0) {
_rc_scan_begin = now;
// // Configure serial port for DSM
dsm_config(_rcs_fd);
rc_io_invert(false);
} else if (_rc_scan_locked
|| now - _rc_scan_begin < rc_scan_max) {
if (newBytes > 0) {
// parse new data
uint8_t st24_rssi, rx_count;
rc_updated = false;
for (unsigned i = 0; i < newBytes; i++) {
/* set updated flag if one complete packet was parsed */
st24_rssi = RC_INPUT_RSSI_MAX;
rc_updated = (OK == st24_decode(_rcs_buf[i], &st24_rssi, &rx_count,
&raw_rc_count, raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
}
if (rc_updated) {
// we have a new ST24 frame. Publish it.
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_ST24;
fill_rc_in(raw_rc_count, raw_rc_values, now,
false, false, frame_drops, st24_rssi);
_rc_scan_locked = true;
}
}
} else {
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SUMD);
}
break;
case RC_SCAN_SUMD:
if (_rc_scan_begin == 0) {
_rc_scan_begin = now;
// // Configure serial port for DSM
dsm_config(_rcs_fd);
rc_io_invert(false);
} else if (_rc_scan_locked
|| now - _rc_scan_begin < rc_scan_max) {
if (newBytes > 0) {
// parse new data
uint8_t sumd_rssi, rx_count;
rc_updated = false;
for (unsigned i = 0; i < newBytes; i++) {
/* set updated flag if one complete packet was parsed */
sumd_rssi = RC_INPUT_RSSI_MAX;
rc_updated = (OK == sumd_decode(_rcs_buf[i], &sumd_rssi, &rx_count,
&raw_rc_count, raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
}
if (rc_updated) {
// we have a new SUMD frame. Publish it.
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SUMD;
fill_rc_in(raw_rc_count, raw_rc_values, now,
false, false, frame_drops, sumd_rssi);
_rc_scan_locked = true;
}
}
} else {
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SUMD);
}
set_rc_scan_state(RC_SCAN_PPM);
break;
case RC_SCAN_PPM:
// skip PPM if it's not supported
#ifdef HRT_PPM_CHANNEL
if (_rc_scan_begin == 0) {
_rc_scan_begin = now;
// Configure timer input pin for CPPM
stm32_configgpio(GPIO_PPM_IN);
rc_io_invert(false);
} else if (_rc_scan_locked
|| now - _rc_scan_begin < rc_scan_max) {
// see if we have new PPM input data
if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal)
&& ppm_decoded_channels > 3) {
// we have a new PPM frame. Publish it.
rc_updated = true;
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM;
fill_rc_in(ppm_decoded_channels, ppm_buffer, now,
false, false, 0);
_rc_scan_locked = true;
}
} else {
// disable CPPM input by mapping it away from the timer capture input
stm32_configgpio(GPIO_PPM_IN & ~(GPIO_AF_MASK | GPIO_PUPD_MASK));
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SBUS);
}
#else // skip PPM if it's not supported
set_rc_scan_state(RC_SCAN_SBUS);
#endif // HRT_PPM_CHANNEL
break;
}
#else // RC_SERIAL_PORT not defined
#ifdef HRT_PPM_CHANNEL
// see if we have new PPM input data
if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal) &&
ppm_decoded_channels > 3) {
if ((ppm_last_valid_decode != _rc_in.timestamp_last_signal)
&& ppm_decoded_channels > 3) {
// we have a new PPM frame. Publish it.
_rc_in.channel_count = ppm_decoded_channels;
if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
_rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
for (uint8_t i = 0; i < _rc_in.channel_count; i++) {
_rc_in.values[i] = ppm_buffer[i];
}
_rc_in.timestamp_publication = ppm_last_valid_decode;
_rc_in.timestamp_last_signal = ppm_last_valid_decode;
_rc_in.rc_ppm_frame_length = ppm_frame_length;
_rc_in.rssi = RC_INPUT_RSSI_MAX;
_rc_in.rc_failsafe = false;
_rc_in.rc_lost = false;
_rc_in.rc_lost_frame_count = 0;
_rc_in.rc_total_frame_count = 0;
rc_updated = true;
fill_rc_in(ppm_decoded_channels, ppm_buffer, hrt_absolute_time(),
false, false, 0);
}
#endif
#endif // HRT_PPM_CHANNEL
#endif // RC_SERIAL_PORT
if (rc_updated) {
/* lazily advertise on first publication */
@ -1363,6 +1603,38 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
#ifdef RC_SERIAL_PORT
case DSM_BIND_START:
/* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
warnx("fmu pwm_ioctl: DSM_BIND_START, arg: %lu", arg);
if (arg == DSM2_BIND_PULSES ||
arg == DSMX_BIND_PULSES ||
arg == DSMX8_BIND_PULSES) {
dsm_bind(DSM_CMD_BIND_POWER_DOWN, 0);
usleep(500000);
dsm_bind(DSM_CMD_BIND_SET_RX_OUT, 0);
dsm_bind(DSM_CMD_BIND_POWER_UP, 0);
usleep(72000);
dsm_bind(DSM_CMD_BIND_SEND_PULSES, arg);
usleep(50000);
dsm_bind(DSM_CMD_BIND_REINIT_UART, 0);
ret = OK;
} else {
ret = -EINVAL;
}
break;
#endif
case MIXERIOCRESET:
if (_mixers != nullptr) {
delete _mixers;
@ -1445,7 +1717,7 @@ ssize_t
PX4FMU::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
uint16_t values[6];
uint16_t values[8];
#ifdef CONFIG_ARCH_BOARD_AEROCORE
@ -1831,6 +2103,26 @@ PX4FMU::gpio_ioctl(struct file *filp, int cmd, unsigned long arg)
return ret;
}
void
PX4FMU::dsm_bind_ioctl(int dsmMode)
{
if (!_armed.armed) {
// mavlink_log_info(_mavlink_fd, "[FMU] binding DSM%s RX", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "-X" : "-X8"));
warnx("[FMU] binding DSM%s RX", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "-X" : "-X8"));
int ret = ioctl(nullptr, DSM_BIND_START,
(dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
if (ret) {
// mavlink_log_critical(_mavlink_fd, "binding failed.");
warnx("binding failed.");
}
} else {
// mavlink_log_info(_mavlink_fd, "[FMU] system armed, bind request rejected");
warnx("[FMU] system armed, bind request rejected");
}
}
namespace
{
@ -2224,7 +2516,7 @@ fmu_main(int argc, char *argv[])
}
if (!strcmp(verb, "info")) {
#ifdef SBUS_SERIAL_PORT
#ifdef RC_SERIAL_PORT
warnx("frame drops: %u", sbus_dropped_frames());
#endif
return 0;

View File

@ -47,6 +47,8 @@
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -58,6 +60,8 @@ PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -69,6 +73,8 @@ PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -80,6 +86,8 @@ PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -91,6 +99,8 @@ PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -102,6 +112,8 @@ PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs

View File

@ -273,6 +273,7 @@ private:
/* cached IO state */
uint16_t _status; ///< Various IO status flags
uint16_t _alarms; ///< Various IO alarms
uint16_t _last_written_arming; ///< the last written arming state reg
/* subscribed topics */
int _t_actuator_controls_0; ///< actuator controls group 0 topic
@ -509,6 +510,7 @@ PX4IO::PX4IO(device::Device *interface) :
_perf_sample_latency(perf_alloc(PC_ELAPSED, "io latency")),
_status(0),
_alarms(0),
_last_written_arming(0),
_t_actuator_controls_0(-1),
_t_actuator_controls_1(-1),
_t_actuator_controls_2(-1),
@ -977,7 +979,7 @@ PX4IO::task_main()
}
if (now >= poll_last + IO_POLL_INTERVAL) {
/* run at 50Hz */
/* run at 50-250Hz */
poll_last = now;
/* pull status and alarms from IO */
@ -988,16 +990,6 @@ PX4IO::task_main()
/* fetch PWM outputs from IO */
io_publish_pwm_outputs();
}
if (now >= orb_check_last + ORB_CHECK_INTERVAL) {
/* run at 5Hz */
orb_check_last = now;
/* try to claim the MAVLink log FD */
if (_mavlink_fd < 0) {
_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
}
/* check updates on uORB topics and handle it */
bool updated = false;
@ -1012,6 +1004,19 @@ PX4IO::task_main()
if (updated) {
io_set_arming_state();
}
}
if (now >= orb_check_last + ORB_CHECK_INTERVAL) {
/* run at 5Hz */
orb_check_last = now;
/* try to claim the MAVLink log FD */
if (_mavlink_fd < 0) {
_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
}
/* check updates on uORB topics and handle it */
bool updated = false;
/* vehicle command */
orb_check(_t_vehicle_command, &updated);
@ -1350,7 +1355,15 @@ PX4IO::io_set_arming_state()
}
}
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
uint16_t new_arming_state = set;
new_arming_state &= ~(clear);
if (_last_written_arming != new_arming_state) {
_last_written_arming = new_arming_state;
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
}
return 0;
}
int

View File

@ -47,6 +47,8 @@
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -58,6 +60,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -69,6 +73,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -80,6 +86,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -91,6 +99,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -102,6 +112,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -113,6 +125,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs
@ -124,6 +138,8 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
*
* Set to 1 to invert the channel, 0 for default direction.
*
* @reboot_required true
*
* @min 0
* @max 1
* @group PWM Outputs

View File

@ -315,13 +315,13 @@ void
ADC::update_system_power(void)
{
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
system_power_s system_power;
system_power_s system_power = {};
system_power.timestamp = hrt_absolute_time();
system_power.voltage5V_v = 0;
for (unsigned i = 0; i < _channel_count; i++) {
if (_samples[i].am_channel == 4) {
if (_samples[i].am_channel == ADC_5V_RAIL_SENSE) {
// it is 2:1 scaled
system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
}
@ -349,13 +349,13 @@ ADC::update_system_power(void)
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V4
system_power_s system_power;
system_power_s system_power = {};
system_power.timestamp = hrt_absolute_time();
system_power.voltage5V_v = 0;
for (unsigned i = 0; i < _channel_count; i++) {
if (_samples[i].am_channel == 4) {
if (_samples[i].am_channel == ADC_5V_RAIL_SENSE) {
// it is 2:1 scaled
system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
}

View File

@ -599,7 +599,7 @@ error:
#endif /* HRT_PPM_CHANNEL */
/**
* Handle the compare interupt by calling the callout dispatcher
* Handle the compare interrupt by calling the callout dispatcher
* and then re-scheduling the next deadline.
*/
static int
@ -750,7 +750,7 @@ hrt_store_absolute_time(volatile hrt_abstime *now)
}
/**
* Initalise the high-resolution timing module.
* Initialise the high-resolution timing module.
*/
void
hrt_init(void)

View File

@ -36,7 +36,7 @@ add_dependencies(run_config mainapp)
foreach(viewer none jmavsim gazebo)
foreach(debugger none gdb lldb ddd valgrind)
foreach(model none iris tailsitter)
foreach(model none iris tailsitter standard_vtol)
if (debugger STREQUAL "none")
if (model STREQUAL "none")
set(_targ_name "${viewer}")

View File

@ -1,32 +1,30 @@
include_directories(${CMAKE_CURRENT_BINARY_DIR})
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-missing-prototypes")
px4_qurt_generate_builtin_commands(
OUT ${CMAKE_BINARY_DIR}/apps.h
MODULE_LIST ${module_libraries})
# Clear -rdynamic flag which fails for hexagon
# this change is scoped in this directory and below
set(CMAKE_SHARED_LIBRARY_LINK_C_FLAGS "")
set(CMAKE_SHARED_LIBRARY_LINK_CXX_FLAGS "")
# Enable build without HexagonSDK to check link dependencies
if ("${QURT_ENABLE_STUBS}" STREQUAL "1")
add_definitions(-DQURT_EXE_BUILD)
add_executable(mainapp
${CMAKE_SOURCE_DIR}/src/platforms/qurt/dspal/dspal_stub.c
${CMAKE_BINARY_DIR}/apps.h)
else()
add_library(mainapp
QURT_BUNDLE(APP_NAME
mainapp
DSP_SOURCES
${CMAKE_SOURCE_DIR}/src/platforms/qurt/dspal/dspal_stub.c
${CMAKE_BINARY_DIR}/apps.h)
${CMAKE_BINARY_DIR}/apps.h
DSP_LINK_LIBS
${module_libraries}
${target_libraries}
df_driver_framework
m
)
endif()
target_link_libraries(mainapp
-Wl,--whole-archive
${module_libraries}
${target_libraries}
df_driver_framework
m
-Wl,--no-whole-archive
-Wl,${TOOLSLIB}/pic/libstdc++.a)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

41
src/firmware/qurt/mainapp.idl Executable file
View File

@ -0,0 +1,41 @@
/****************************************************************************
* Copyright (c) 2015 Mark Charlebois. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name ATLFlight nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef MAINAPP_IDL
#define MAINAPP_IDL
#include "AEEStdDef.idl"
interface mainapp{
uint32 test();
};
#endif /*MAINAPP_IDL*/

@ -1 +1 @@
Subproject commit 2ae8d8118db0e95867cd1946d5b8b85d7e4ef9d3
Subproject commit 98c4dd676f8ac8c44a377f95864cb29a992a549e

@ -1 +1 @@
Subproject commit 2af5856361adf7ede444cc7f3fd6cf725dfa0213
Subproject commit 8d0022ab1e65543124efd2f55b4e72b9e672cd61

View File

@ -51,7 +51,7 @@ enum LaunchDetectionResult {
up and still be set to 'throttlePreTakeoff'.
For instance this is used to have a delay for the motor
when launching a fixed wing aircraft from a bungee */
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, the controller should control
attitude and also throttle up the motors. */
};

View File

@ -54,7 +54,7 @@
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
/**
* Catapult accelerometer theshold.
* Catapult accelerometer threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
/**
* Catapult time theshold.
* Catapult time threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*

@ -1 +1 @@
Subproject commit b9d6cac199bd4476c6268f7eba76c01bf29f0295
Subproject commit ce30542dbaa3e6f5e68b742a34cda993a351e15d

View File

@ -615,7 +615,7 @@ sbus_decode(uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issueing return-to-launch!!! */
* e.g. by prematurely issuing return-to-launch!!! */
*sbus_failsafe = false;
*sbus_frame_drop = true;

View File

@ -66,7 +66,12 @@
#ifdef CONFIG_ARCH_BOARD_SITL
#define HW_ARCH "LINUXTEST"
#endif
#ifdef CONFIG_ARCH_BOARD_EAGLE
#define HW_ARCH "LINUXTEST"
#endif
#ifdef CONFIG_ARCH_BOARD_RPI2
#define HW_ARCH "LINUXTEST"
#endif
#endif /* VERSION_H_ */

View File

@ -2,7 +2,7 @@ function [xa_apo,Pa_apo,Rot_matrix,eulerAngles,debugOutput]...
= AttitudeEKF(approx_prediction,use_inertia_matrix,zFlag,dt,z,q_rotSpeed,q_rotAcc,q_acc,q_mag,r_gyro,r_accel,r_mag,J)
%LQG Postion Estimator and Controller
%LQG Position Estimator and Controller
% Observer:
% x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n])
% x[n+1|n] = Ax[n|n] + Bu[n]

View File

@ -499,7 +499,7 @@ void AttitudeEKF(unsigned char approx_prediction, unsigned char
float b_z[6];
/* LQG Postion Estimator and Controller */
/* LQG Position Estimator and Controller */
/* Observer: */
/* x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n]) */
/* x[n+1|n] = Ax[n|n] + Bu[n] */

View File

@ -595,7 +595,8 @@ int do_level_calibration(int mavlink_fd) {
param_get(pitch_offset_handle, &pitch_offset_current);
param_get(board_rot_handle, &board_rot_current);
if (board_rot_current == 0) {
// give attitude some time to settle if there have been changes to the board rotation parameters
if (board_rot_current == 0 && fabsf(roll_offset_current) < FLT_EPSILON && fabsf(pitch_offset_current) < FLT_EPSILON ) {
settle_time = 0;
}

View File

@ -417,7 +417,7 @@ int commander_main(int argc, char *argv[])
/* see if we got a home position */
if (status.condition_home_position_valid) {
if (TRANSITION_CHANGED == arm_disarm(true, mavlink_fd_local, "command line")) {
if (TRANSITION_DENIED != arm_disarm(true, mavlink_fd_local, "command line")) {
vehicle_command_s cmd = {};
cmd.target_system = status.system_id;
@ -1509,12 +1509,12 @@ int commander_thread_main(int argc, char *argv[])
/* EPH / EPV */
param_get(_param_eph, &eph_threshold);
param_get(_param_epv, &epv_threshold);
}
/* Set flag to autosave parameters if necessary */
if (updated && autosave_params != 0) {
/* trigger an autosave */
need_param_autosave = true;
/* Set flag to autosave parameters if necessary */
if (updated && autosave_params != 0 && param_changed.saved == false) {
/* trigger an autosave */
need_param_autosave = true;
}
}
orb_check(sp_man_sub, &updated);
@ -1570,11 +1570,12 @@ int commander_thread_main(int argc, char *argv[])
/* and the system is not already armed (and potentially flying) */
!armed.armed) {
bool chAirspeed = false;
bool hotplug_timeout = hrt_elapsed_time(&commander_boot_timestamp) > HOTPLUG_SENS_TIMEOUT;
bool chAirspeed = false;
bool hotplug_timeout = hrt_elapsed_time(&commander_boot_timestamp) > HOTPLUG_SENS_TIMEOUT;
/* Perform airspeed check only if circuit breaker is not
* engaged and it's not a rotary wing */
* engaged and it's not a rotary wing
*/
if (!status.circuit_breaker_engaged_airspd_check && !status.is_rotary_wing) {
chAirspeed = true;
}
@ -2284,6 +2285,15 @@ int commander_thread_main(int argc, char *argv[])
mavlink_log_critical(mavlink_fd, "main state transition denied");
}
/* check throttle kill switch */
if (sp_man.kill_switch == manual_control_setpoint_s::SWITCH_POS_ON) {
/* set lockdown flag */
armed.lockdown = true;
} else if (sp_man.kill_switch == manual_control_setpoint_s::SWITCH_POS_OFF) {
armed.lockdown = false;
}
/* no else case: do not change lockdown flag in unconfigured case */
} else {
if (!status.rc_input_blocked && !status.rc_signal_lost) {
mavlink_log_critical(mavlink_fd, "MANUAL CONTROL LOST (at t=%llums)", hrt_absolute_time() / 1000);
@ -2714,7 +2724,7 @@ control_status_leds(vehicle_status_s *status_local, const actuator_armed_s *actu
}
}
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V1) || defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
/* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
if (actuator_armed->armed) {
@ -3018,8 +3028,8 @@ set_control_mode()
control_mode.flag_control_attitude_enabled = true;
control_mode.flag_control_altitude_enabled = true;
control_mode.flag_control_climb_rate_enabled = true;
control_mode.flag_control_position_enabled = true;
control_mode.flag_control_velocity_enabled = true;
control_mode.flag_control_position_enabled = !status.in_transition_mode;
control_mode.flag_control_velocity_enabled = !status.in_transition_mode;
control_mode.flag_control_termination_enabled = false;
break;

View File

@ -75,11 +75,11 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
} ArmingTransitionVolatileState_t;
// This structure represents a test case for arming_state_transition. It contains the machine
// state prior to transtion, the requested state to transition to and finally the expected
// state prior to transition, the requested state to transition to and finally the expected
// machine state after transition.
typedef struct {
const char* assertMsg; // Text to show when test case fails
ArmingTransitionVolatileState_t current_state; // Machine state prior to transtion
ArmingTransitionVolatileState_t current_state; // Machine state prior to transition
hil_state_t hil_state; // Current vehicle_status_s.hil_state
bool condition_system_sensors_initialized; // Current vehicle_status_s.condition_system_sensors_initialized
bool safety_switch_available; // Current safety_s.safety_switch_available

View File

@ -97,6 +97,9 @@ static const char * const state_names[vehicle_status_s::ARMING_STATE_MAX] = {
"ARMING_STATE_IN_AIR_RESTORE",
};
static hrt_abstime last_preflight_check = 0; ///< initialize so it gets checked immediately
static int last_prearm_ret = 1; ///< initialize to fail
transition_result_t
arming_state_transition(struct vehicle_status_s *status, ///< current vehicle status
const struct safety_s *safety, ///< current safety settings
@ -132,12 +135,18 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
}
/* re-run the pre-flight check as long as sensors are failing */
if (!status->condition_system_sensors_initialized
&& (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED ||
new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY)
&& status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
&& (new_arming_state == vehicle_status_s::ARMING_STATE_ARMED
|| new_arming_state == vehicle_status_s::ARMING_STATE_STANDBY)
&& status->hil_state == vehicle_status_s::HIL_STATE_OFF) {
prearm_ret = preflight_check(status, mavlink_fd, false /* pre-flight */);
status->condition_system_sensors_initialized = !prearm_ret;
if (last_preflight_check == 0 || hrt_absolute_time() - last_preflight_check > 1000 * 1000) {
prearm_ret = preflight_check(status, mavlink_fd, false /* pre-flight */);
status->condition_system_sensors_initialized = !prearm_ret;
last_preflight_check = hrt_absolute_time();
last_prearm_ret = prearm_ret;
} else {
prearm_ret = last_prearm_ret;
}
}
/*

Some files were not shown because too many files have changed in this diff Show More