aboutsummaryrefslogtreecommitdiff
Commit message (Collapse)AuthorAgeFilesLines
* Hack to make flow controll to compileJulian Oes2013-06-163-1/+9
|
* Merge branch 'pid_fixes' into new_state_machineJulian Oes2013-06-1523-90/+2254
|\
| * Added a filter parameter to the pid functionJulian Oes2013-06-157-31/+40
| | | | | | | | | | Conflicts: apps/multirotor_pos_control/multirotor_pos_control.c
| * Use the pid library in the rate controller and change de implementation of ↵Julian Oes2013-06-154-67/+46
| | | | | | | | | | | | | | | | | | the D part Conflicts: src/modules/multirotor_att_control/multirotor_rate_control.c src/modules/systemlib/pid/pid.c src/modules/systemlib/pid/pid.h
| * Merge pull request #303 from samized/flowboard_masterLorenz Meier2013-06-1416-0/+2176
| |\ | | | | | | Add PX4Flow board modules and corresponding ORB msgs.
| | * Add PX4Flow board modules and corresponding ORB msgs.samuezih2013-06-1416-0/+2176
| |/
* | Controllers should not access state machine anymore but access the ↵Julian Oes2013-06-1512-168/+182
| | | | | | | | vehicle_control_mode flags
* | Beep when mode is not possibleJulian Oes2013-06-142-3/+19
| |
* | Arming with IO working nowJulian Oes2013-06-142-6/+9
| |
* | Introduced new actuator_safety topicJulian Oes2013-06-1422-193/+424
| |
* | Fixed param saveJulian Oes2013-06-131-1/+1
| |
* | Merge remote-tracking branch 'upstream/master' into new_state_machineJulian Oes2013-06-131-2/+0
|\|
| * Hotfix: Excluded sdlog app from standard build, still keeping code in place ↵Lorenz Meier2013-06-131-2/+0
| | | | | | | | for now
* | Two hacks here to make it compileJulian Oes2013-06-122-10/+17
| |
* | Merge remote-tracking branch 'upstream/master' into new_state_machineJulian Oes2013-06-12329-121360/+5863
|\| | | | | | | | | Conflicts: src/examples/fixedwing_control/main.c
| * Merge pull request #299 from DrTon/sdlog2Lorenz Meier2013-06-092-16/+38
| |\ | | | | | | sdlog2: RC (RC controls) and OUT0 (actuator 0 output) messages added
| | * Merge branch 'master' into sdlog2Anton Babushkin2013-06-085-6/+6
| | |\ | | |/ | |/|
| * | Merge branch 'master' of github.com:PX4/FirmwareLorenz Meier2013-06-0711-48/+188
| |\ \
| | * \ Merge pull request #297 from DrTon/sdlog2Lorenz Meier2013-06-074-25/+100
| | |\ \ | | | | | | | | | | sdlog2: new log messages added, ajustable log buffer
| | * | | Hotfix: Renamed max NSH argument variable to correct defineLorenz Meier2013-06-071-2/+2
| | | | |
| * | | | Hotfix: Make maxoptimization configurable from the shell via ↵Lorenz Meier2013-06-074-4/+4
| | | | | | | | | | | | | | | | | | | | MAXOPTIMIZATION=-O0 V=1 make archives
| | | | * sdlog2: RC (RC controls) and OUT0 (actuator 0 output) messages added, print ↵Anton Babushkin2013-06-082-16/+38
| | | |/ | | | | | | | | | | | | statistics to mavlink console
| | | * sdlog2 minor fixAnton Babushkin2013-06-071-3/+0
| | | |
| | | * sdlog2 -b option (log buffer size) added, minor cleanupAnton Babushkin2013-06-073-17/+40
| | | |
| | | * sdlog2 fixesAnton Babushkin2013-06-071-1/+3
| | | |
| | | * Merge branch 'master' into sdlog2Anton Babushkin2013-06-0719-90/+1155
| | | |\ | | | |/ | | |/|
| | * | Config change: Set USB console as default.Lorenz Meier2013-06-071-4/+4
| | | |
| | * | Hotfix: Add an IO pass mixer with 8 outputsLorenz Meier2013-06-071-0/+38
| | | |
| | * | Hotfix: Allow the IO mixer loading to load larger mixers, fix up the px4io ↵Lorenz Meier2013-06-071-2/+19
| | | | | | | | | | | | | | | | test command to allow a clean exit
| | * | Hotfix: Enlarge the buffer size for mixers, ensure that reasonable setups ↵Lorenz Meier2013-06-071-2/+2
| | | | | | | | | | | | | | | | with 16 outputs can work
| | * | Hotfix: Make IOs mixer loading pedantic to make sure the full mixer loadsLorenz Meier2013-06-071-6/+12
| | | |
| | * | Hotfix: fix building firmware parallelpx4dev2013-06-062-7/+11
| |/ /
| * | Merge branch 'master' of github.com:PX4/FirmwareLorenz Meier2013-06-0615-28/+2903
| |\ \
| | * | Hotfix: Disable instrumentation on IOLorenz Meier2013-06-061-2/+10
| | | |
| | * | Hotfix: Added missing headerLorenz Meier2013-06-061-0/+1
| | | |
| | * | Minor cleanupLorenz Meier2013-06-061-5/+5
| | | |
| | * | Hotfix: Fix typos in tutorial codeLorenz Meier2013-06-061-25/+28
| | | |
| | * | Removed big RAM consumer (inactive filter)Lorenz Meier2013-06-061-1/+1
| | | |
| | * | Merge pull request #284 from limhyon/masterLorenz Meier2013-06-066-0/+954
| | |\ \ | | | | | | | | | | Nonlinear complementary SO(3) filter has been implemented.
| | | * | Add detailed documentation for SO3 gains tuning.Hyon Lim (Retina)2013-06-063-15/+50
| | | | | | | | | | | | | | | | | | | | USB nsh has been removed.
| | | * | GPL Licensed code has been removedHyon Lim (Retina)2013-05-298-1852/+1
| | | | |
| | | * | Visualization code has been added.Hyon Lim (Retina)2013-05-2910-2/+1882
| | | | |
| | | * | Merge branch 'master' of https://github.com/limhyon/FirmwareHyon Lim (Retina)2013-05-290-0/+0
| | | |\ \
| | | | * | I finished to implement nonlinear complementary filter on the SO(3).Hyon Lim (Retina)2013-05-291-56/+120
| | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | The previous problem was roll,pitch and yaw angle from quaternion. Now it is fixed. 1-2-3 Euler representation is used. Also accelerometer sign change has been applied.
| | | * | | I finished to implement nonlinear complementary filter on the SO(3).Hyon Lim (Retina)2013-05-291-56/+120
| | | |/ / | | | | | | | | | | | | | | | | | | | | | | | | | The previous problem was roll,pitch and yaw angle from quaternion. Now it is fixed. 1-2-3 Euler representation is used. Also accelerometer sign change has been applied.
| | | * | Merge remote-tracking branch 'upstream/master'Hyon Lim (Retina)2013-05-289-257/+629
| | | |\ \ | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | - Mikrokopter BLCTRL seems to be updated - HMC5883L calibration problem has been corrected. (This is because of RAM mis allocation?) See https://groups.google.com/forum/?fromgroups#!topic/px4users/yTYJiDBBKfo - Fixed wing control updated https://groups.google.com/forum/?fromgroups#!topic/px4users/s7owpvZN8UI - GPIO module has been removed. - STM32 DRV updated
| | | * | | Test flight has been performed with nonlinear SO(3) attitude estimator.Hyon Lim (Retina)2013-05-232-114/+116
| | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | Here are few observations: - When the system initialized, roll angle is initially reversed. As filter converged, it becomes normal. - I put a negative sign on roll, yaw. It should naturally has right sign, but I do not know why for now. Let me investigate again. - Gain : I do not know what gain is good for quadrotor flight. Let me take a look Ardupilot gain in the later. Anyway, you can fly with this attitude estimator.
| | | * | | To use freeIMU processing visualization tool, I have implemented float ↵Hyon Lim (Retina)2013-05-231-77/+196
| | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | | number transmission over uart (default /dev/ttyS2, 115200) But this not tested yet. I should.
| | | * | | Roll pitch yaw should be verified againHyon Lim (Retina)2013-05-232-94/+94
| | | | | |
| | | * | | I do not know why roll angle is not correct. But system looks okayHyon Lim (Retina)2013-05-231-34/+38
| | | | | |