diff --git a/Readme.md b/README.md similarity index 91% rename from Readme.md rename to README.md index e26a790ca821a2d432cab59e81c2f984d7347f19..c254b84a3114ab26eb5a83853552e4229411f933 100644 --- a/Readme.md +++ b/README.md @@ -1,11 +1,12 @@ [](https://git.ece.iastate.edu/danc/MicroCART_17-18/commits/master) + # MicroCART _Microprocessor Controlled Aerial Robotics Team_ **Project Statement**: "To create a modular platform for research in controls and embedded systems." -Since 2006, MicroCART has been building aerial robots. Currently, we are +Since 1998, MicroCART has been building aerial robots. Currently, we are building a quadcopter that can fly autonomously. MicroCART has 3 areas of development: @@ -26,13 +27,14 @@ MicroCART has 3 areas of development: ## Sections [Quadcopter](quad/README.md) [Ground Station](groundStation/README.md) -[Controls](controls/README.md) +[Controls](controls/README.md) ## Documentation [How to demo the quadcopter](documentation/how_to_demo.md) [How to charge the LiPo batteries](documentation/how_to_charge_lipo.md) [Continuous Integration (automatic build process) FAQ](documentation/ci_faq.md) [How to document things on Gitlab](documentation/how_to_document_things_on_gitlab.md) +[How to update the website](website/README.md) # Stable Releases -To browse stable releases from previous teams, view the [Tags](/../tags). \ No newline at end of file +To browse stable releases from previous teams, view the [Tags](/../tags). diff --git a/controls/DataAnalysisTool/Tool/DataAnalysis.m b/controls/DataAnalysisTool/Tool/DataAnalysis.m index a7b87317346c0d2289901a5cefe5c6aec86e4ca8..b8cb1710ed7405ed8798878d1e2a0e64cd135f7b 100644 --- a/controls/DataAnalysisTool/Tool/DataAnalysis.m +++ b/controls/DataAnalysisTool/Tool/DataAnalysis.m @@ -51,9 +51,9 @@ backgnd = [1 1 1]; % rgb array for background color of the plot %% DO NOT MODIFY %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -fpath = ''; +fpath = '/local/ucart/Documents/MicroCART_17-18/groundStation/logs/'; if(isempty(fname)) - [fname, fpath] = uigetfile('.txt','Select log file'); + [fname, fpath] = uigetfile('.txt','Select log file', fpath); end % storing file options in the structure @@ -100,4 +100,6 @@ plot_data(expData, params.plotting); % main.params = params; % main.expData = expData; % clearvars -except main; -% save main main; \ No newline at end of file +% save main main; + +clear plot; \ No newline at end of file diff --git a/controls/DataAnalysisTool/Tool/simplePlots.m b/controls/DataAnalysisTool/Tool/simplePlots.m index a1087dfda7ccb05ff6f95b7edc4d465056ba6f77..c969045e174281faa600fa02bb38089cb586375e 100644 --- a/controls/DataAnalysisTool/Tool/simplePlots.m +++ b/controls/DataAnalysisTool/Tool/simplePlots.m @@ -40,22 +40,30 @@ linkaxes([ax1, ax2], 'x'); ax2 = subplot(2,2,1); plot(expData.Time.data, expData.X_Setpoint_Constant.data - expData.VRPN_X_Constant.data); title('X error'); +ylabel('meters'); +xlabel('time (s)'); ax1 = subplot(2,2,2); plot(expData.Time.data, expData.X_pos_PID_Correction.data); -title('x output'); +title('x controller output'); +ylabel('rad'); +xlabel('time (s)'); ax3 = subplot(2,2,3); plot(expData.Time.data, expData.Pitch_PID_Correction.data); hold on; -plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* 10); +%plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* 10); title('pitch output'); -legend('output', 'Pitch x10'); +ylabel('rad/s'); +%legend('output', 'Pitch x10'); +xlabel('time (s)'); ax4 = subplot(2,2,4); plot(expData.Time.data, expData.Pitch_Rate_PID_Correction.data); hold on; -plot(expData.Time.data, expData.gyro_y.data .* 100000); -legend('output', 'Pitch rate x100000'); +%plot(expData.Time.data, expData.gyro_y.data * 0.1); +%legend('output', 'Pitch rate x100000'); +ylabel('Normalized PWM'); title('pitch rate output'); +xlabel('time (s)'); linkaxes([ax1, ax2, ax3, ax4], 'x'); %% X pos controller flow @@ -97,7 +105,7 @@ all_motors = expData.Signal_Mixer_MOTOR_0.data + expData.Signal_Mixer_MOTOR_1.da expData.Signal_Mixer_MOTOR_2.data + expData.Signal_Mixer_MOTOR_3.data; ax1 = subplot(1, 2, 1); plot(expData.Time.data, all_motors ./ 4); hold on; -plot(expData.Time.data, expData.RC_Throttle_Constant.data); hold on; +%plot(expData.Time.data, expData.RC_Throttle_Constant.data); hold on; plot(expData.Time.data, expData.Pitch_Rate_PID_Correction.data); hold on; plot(expData.Time.data, expData.Roll_Rate_PID_Correction.data); hold on; plot(expData.Time.data, expData.Yaw_Rate_PID_Correction.data); @@ -109,11 +117,11 @@ linkaxes([ax1, ax2], 'x'); %% ax1 = subplot(1, 2, 1); -plot(expData.Time.data, expData.Pitch_Constant.data .* (180 / pi)); hold on; grid minor +%plot(expData.Time.data, expData.Pitch_Constant.data .* (180 / pi)); hold on; grid minor plot(expData.Time.data, expData.VRPN_Pitch_Constant.data .* (180 / pi)); legend('imu', 'vrpn'); ax2 = subplot(1, 2, 2); -plot(expData.Time.data, expData.Roll_Constant.data .* (180 / pi)); hold on; grid minor +%plot(expData.Time.data, expData.Roll_Constant.data .* (180 / pi)); hold on; grid minor plot(expData.Time.data, expData.VRPN_Roll_Constant.data .* (180 / pi)); legend('imu', 'vrpn'); linkaxes([ax1, ax2], 'x'); @@ -163,8 +171,8 @@ linkaxes([ax1, ax2, ax3, ax4], 'x'); %% vel flow figure; ax2 = subplot(2,2,1); -plot(expData.Time.data, expData.OF_Offset_Angle_Rotated_X.data - expData.RC_Pitch_Constant.data); hold on; plot(expData.Time.data, expData.OF_Offset_Angle_Rotated_X.data); hold on; +%plot(expData.Time.data, expData.OF_Offset_Angle_Rotated_X.data); hold on; %plot(expData.Time.data, expData.X_Vel_Correction.data); hold on; %plot(expData.Time.data, [0; raw_derivative]); title('X velocity error'); @@ -187,6 +195,7 @@ title('pitch rate output'); linkaxes([ax1, ax2, ax3, ax4], 'x'); %% +figure; ax1 = subplot(2, 1, 1); plot(expData.Time.data, expData.Alt_Setpoint_Constant.data - expData.VRPN_Alt_Constant.data); hold on; plot(expData.Time.data, expData.Alt_Setpoint_Constant.data); hold on; @@ -222,12 +231,12 @@ figure; plot(expData.Time.data, expData.Lidar_Constant.data); hold on; plot(expData.Time.data, expData.VRPN_Alt_Constant.data); -angle = sqrt(expData.Roll_Constant.data.^2 + expData.VRPN_Pitch_Constant.data.^2); -corrected = expData.Lidar_Constant.data .* cos(angle); +%angle = sqrt(expData.Roll_Constant.data.^2 + expData.VRPN_Pitch_Constant.data.^2); +%corrected = expData.Lidar_Constant.data .* cos(angle); %plot(expData.Time.data, corrected); -legend('lidar', 'vrpn', 'angle corrected'); +legend('lidar', 'vrpn'); -linkaxes([ax1, ax2], 'x'); +%linkaxes([ax1, ax2], 'x'); %% Sonar filtered_sonar = []; @@ -246,33 +255,159 @@ plot(expData.Time.data, -expData.Flow_Distance_Constant.data + alt_offset); hold plot(expData.Time.data, expData.VRPN_Alt_Constant.data); plot(expData.Time.data, -filtered_sonar + alt_offset); legend('sonar', 'vrpn', 'dumb filter'); -%% +%% THE ONE figure; -offsetX = -expData.OF_Integrate_X_Integrated.data(1) - expData.VRPN_X_Constant.data(1); -offsetY = -expData.OF_Integrate_Y_Integrated.data(1) - expData.VRPN_Y_Constant.data(1); +% offsetX = -expData.OF_Integrate_X_Integrated.data(1) - expData.VRPN_X_Constant.data(1); +% offsetY = -expData.OF_Integrate_Y_Integrated.data(1) - expData.VRPN_Y_Constant.data(1); +offsetX = 0; +offsetY = 0; -ax1 = subplot(2, 1, 1); -plot(expData.Time.data, -expData.OF_Integrate_X_Integrated.data - offsetX); hold on; +ax1 = subplot(3, 1, 1); +plot(expData.Time.data, expData.OF_Integrate_X_Integrated.data - offsetX); hold on; grid minor plot(expData.Time.data, expData.VRPN_X_Constant.data); -legend('OF X Position', 'VRPN X Position'); +plot(expData.Time.data, expData.X_Setpoint_Constant.data); +legend('OF X Position', 'VRPN X Position', 'X setpoint'); xlabel('Time (s)'); ylabel('Displacement (m)'); hold off; -ax2 = subplot(2, 1, 2); -plot(expData.Time.data, -expData.OF_Integrate_Y_Integrated.data - offsetY); hold on; +ax2 = subplot(3, 1, 2); +plot(expData.Time.data, expData.OF_Integrate_Y_Integrated.data - offsetY); hold on; grid minor plot(expData.Time.data, expData.VRPN_Y_Constant.data); -legend('OF Y Position', 'VRPN Y Position'); +plot(expData.Time.data, expData.Y_Setpoint_Constant.data); +legend('OF Y Position', 'VRPN Y Position', 'Y setpoint'); xlabel('Time (s)'); ylabel('Displacement (m)'); hold off; -linkaxes([ax1, ax2]); +ax3 = subplot(3, 1, 3); +plot(expData.Time.data, expData.Lidar_Constant.data); hold on; grid minor +plot(expData.Time.data, expData.VRPN_Alt_Constant.data); +plot(expData.Time.data, expData.Alt_Setpoint_Constant.data); +legend('Lidar Z Position', 'VRPN Z Position', 'Z setpoint'); +xlabel('Time (s)'); +ylabel('Displacement (m)'); +hold off; + +linkaxes([ax1, ax2, ax3], 'x'); + + +linkaxes([ax1, ax2, ax3], 'x'); +%% Error Graphs +figure; +ax1 = subplot(2,1,1); +plot(expData.Time.data, expData.X_Setpoint_Constant.data - expData.OF_Integrate_X_Integrated.data); +title('X error'); +ax2 = subplot(2,1,2); +plot(expData.Time.data, expData.Y_Setpoint_Constant.data - expData.OF_Integrate_Y_Integrated.data); +title('Y error'); -%% Integarted gyro yaw +%% Integarted gyro0.55 yaw figure; -plot(expData.Time.data, cumtrapz(expData.gyro_z.data + 0.0088)); hold on; -plot(expData.Time.data, expData.Yaw_Constant.data); hold on; +gyro_yaw = 0.005 * cumtrapz(expData.gyro_z.data + 0.0073); +plot(expData.Time.data, (180/pi) * gyro_yaw); hold on; +plot(expData.Time.data, expData.Yaw_Constant.data * 180/pi); hold on; legend('Integrated gyro z', 'actual yaw'); +ylabel('Yaw (degrees)'); +xlabel('Time (s)'); + +%% +figure; +angleOffset = 0.62204 + gyro_yaw; + +FlowVelX = expData.Flow_Vel_X_Constant.data.*cos(angleOffset) - expData.Flow_Vel_Y_Constant.data.*sin(angleOffset); +FlowVelY = expData.Flow_Vel_X_Constant.data.*sin(angleOffset) + expData.Flow_Vel_Y_Constant.data.*cos(angleOffset); + +fc = 10; +FlowVelX = BiquadFilter(FlowVelX, 200, fc); +FlowVelY = BiquadFilter(FlowVelY, 200, fc); + +flowX = zeros(1, length(expData.Time.data)); + +driftX = 0; +driftY = 0; + +flowX(1) = expData.VRPN_X_Constant.data(1); +for n = 2:length(flowX) + flowX(n) = flowX(n-1) + 0.005*(FlowVelX(n) - driftX); +end + +flowY = zeros(1, length(expData.Time.data)); +flowY(1) = expData.VRPN_Y_Constant.data(1); +for n = 2:length(flowY) + flowY(n) = flowY(n-1) + 0.005*(FlowVelY(n) - driftY); +end + +ax1 = subplot(2, 1, 1); +plot(expData.Time.data, flowX); hold on; +plot(expData.Time.data, expData.VRPN_X_Constant.data); +%legend('OF Integrated X Position'); +legend('OF Integrated X', 'VRPN X'); +%legend('OF Integrated X Position', 'Approximate Max X Position (measured with tape measure)'); +xlabel('Time (s)'); +ylabel('Position (m)'); +hold off; + +ax2 = subplot(2, 1, 2); +plot(expData.Time.data, flowY); hold on; +plot(expData.Time.data, expData.VRPN_Y_Constant.data); +%legend('OF Integrated Y Position'); +legend('OF Integrated Y', 'VRPN Y'); +%legend('OF Integrated Y Position', 'Approximate Max Y Position (measured with tape measure)'); +xlabel('Time (s)'); +ylabel('Position (m)'); +hold off; + +linkaxes([ax1 ax2]); +%% +figure; +ax1 = subplot(2, 1, 1); +plot(expData.Time.data, expData.Flow_Quality_Constant.data); +ax2 = subplot(2, 1, 2); +plot(expData.Time.data, expData.Lidar_Constant.data); hold on; +plot(expData.Time.data, expData.VRPN_Alt_Constant.data); +linkaxes([ax1 ax2], 'x'); + +%% +figure; +ax1 = subplot(3, 1, 1); +plot(expData.Time.data, expData.mag_x.data); +ax2 = subplot(3, 1, 2); +plot(expData.Time.data, expData.mag_y.data); +ax3 = subplot(3, 1, 3); +plot(expData.Time.data, expData.mag_z.data); +linkaxes([ax1 ax2 ax3], 'x'); + +%% +figure; +filtX = BiquadFilter(expData.mag_x.data+33.9844, 200, 1); +filtY = BiquadFilter(expData.mag_y.data-40.4922, 200, 1); + +magYaw = atan2(-filtY, -filtX); +gyroYaw = cumtrapz(expData.gyro_z.data - 0.008) * 0.005; + +ax1 = subplot(3, 1, 1); +plot(expData.Time.data, magYaw*180/pi); +ax2 = subplot(3, 1, 2); +plot(expData.Time.data, gyroYaw*180/pi); +ax3 = subplot(3, 1, 3); +plot(expData.Time.data, expData.Mag_Yaw_Constant.data*180/pi); + +linkaxes([ax1 ax2 ax3], 'x'); + +%% +mag = expData.mag_z.data; + +count = 0; +for n = 2:length(mag) + if mag(n) == mag(n-1) + count = count + 1; + if count >= 10 + disp(['Stall detected at index ' num2str(n)]); + end + else + count = 0; + end +end \ No newline at end of file diff --git a/controls/README.md b/controls/README.md index 456ed8fa19fc7eadf759c1bcef4e33d3bffdbb7b..29c4bc1e2d9d0bced898e76bbd4448fad85b9172 100644 --- a/controls/README.md +++ b/controls/README.md @@ -1,3 +1,6 @@ # Controls -_TODO_ \ No newline at end of file +This folder contains the files used in developing the model of the quadcopter. + +## Documentation +[Measuring Motor Resistance](documentation/MeasuringMotorResistance.pdf) \ No newline at end of file diff --git a/controls/documentation/MeasuringMotorResistance.pdf b/controls/documentation/MeasuringMotorResistance.pdf new file mode 100644 index 0000000000000000000000000000000000000000..317655a7dfb96fdc6b3b8c16b7056f38ecceea0a Binary files /dev/null and b/controls/documentation/MeasuringMotorResistance.pdf differ diff --git a/documentation/how_to_demo.md b/documentation/how_to_demo.md index 104c64bc20852f6dcbcb9bea5a1c380d6bae8d63..c021dcf10c54eea6b382ff107061ae7fcb67e501 100644 --- a/documentation/how_to_demo.md +++ b/documentation/how_to_demo.md @@ -21,7 +21,7 @@ Follow this How-To to get the quadcopter up and running in Coover 3050. 7. Now you should be able to move the quadcopter trackable around in the tracking area, and see it update in real-time on the screen. ## Setup Ground Station -On the ground station computer (Co3050-09), log in with the following credentials. +On the ground station computer (Co3050-microcart), log in with the following credentials. username: `ucart`<br> password: `microcart` @@ -39,11 +39,6 @@ make vrpn make ``` -And set the wifi environment variable if you want to connect to the quad over wifi. -```bash -$ UCART_USE_WIFI=true -``` - ## Setup Transmitter The RC transmitter is used to manually control the quad. 1. Ensure the transmitter has the following state before turning it on: @@ -76,18 +71,12 @@ Execute the following on the ground station from the root of the ground station In one terminal, run the backend: ```bash -UCART_SOCKET=./ucart.socket ./BackEnd -``` - -In another terminal, run the monitor: -```bash -UCART_SOCKET=./ucart.socket ./Cli monitor -f +./BackEnd ``` Finally, in another terminal, export the socket path, and then execute any CLI commands that you like: ```bash -export UCART_SOCKET=./ucart.socket -./Cli setpid --pitch -p 1.000 +./Cli setparam 'X pos PID' 'Setpoint' 1.000 # ... other CLI commands ``` diff --git a/groundStation/README.md b/groundStation/README.md index e14675ab8ad6eb0b870f87355b94a0778eae994c..f9902a1c4b154c3862e52dd71a220caabf871b40 100644 --- a/groundStation/README.md +++ b/groundStation/README.md @@ -4,34 +4,39 @@ First, if submodules were not recursevly added through git. Run this command if you have made any attempt to make vrpn manually. run - 'git submodule update --init --recursive' +```bash + git submodule update --init --recursive +``` Now that you have all of the files necissary. cd into the groundstation folder. +```bash cd groundStation make vrpn make +``` -run the program with sudo privledges +run the program with privledges +```bash ./BackEnd +``` -If you wish to change the way the backend communicates to the quad and vice versa, look at src/config.h. - This provides a list of environment variables which you can set and use for your computer or time of use. +## Changing Defaults +If you wish to change the way the backend communicates to the quad and vice versa, look at `src/config.h`. +This provides a list of environment variables which you can set and use for your computer or time of use. - -## Modifying -See MODIFYING for the software architecture/organization and how to add new functionality. - ## Using -First, the backend daemon must be running. Run the backend with ./BackEnd. Note -the environment variables in config.h, especially the backend socket path. The backend -requires root for bluetooth, but can run as a normal user with TCP, as long as the +First, the backend daemon must be running. Run the backend with +```bash + ./BackEnd +``` +**Note:** The backend requires root for bluetooth, but can run as a normal user with TCP, as long as the socket path is writable by the user. Once the backend is running, various CLI tools can be used to view the state of the quad and send commands. Each of these tools is given as the first argument -to the CLI program, for example, to get a node output the quad, use `cli getoutput`. Note that +to the CLI program, for example, to get a node output from the quad, use `cli getoutput`. Note that the backend socket environment variable must be set to the same value as it was for the backend. The CLI program also supports busybox-style symbolic links. For example, if there is a symlink named `getoutput` that points to the `cli` binary, @@ -39,48 +44,41 @@ running the `getoutput` program will effectively run `cli getoutput`. The names of the binaries is subject to change. -For a list of cli commands and more in depth usage explainations, use the --help flag. -'./Cli --help' +For a list of cli commands and more in depth usage explainations, use the `--help` flag. +```bash + ./Cli --help +``` -For help with the specific cli command you are running, use the --help flag once again. -'./Cli getoutput --help' +For help with the specific cli command you are running, use the `--help` flag once again. +```bash + ./Cli getoutput --help +``` ### Example In one terminal or screen, run the backend: -`./BackEnd` +```bash + ./BackEnd +``` This will activate the quad and the backend, and the backend will be available for -connections from the frontend tools. One useful tool is the getnodes. In another +connections from the frontend tools. One useful tool is the `getnodes`. In another terminal window, run -`./Cli getnodes` +```bash + ./Cli getnodes +``` or alternatively with symlinks -`./getnodes` - -This will fetch the block_id, type_id and name of every node in the current graph - -You can run any number of any combination of frontend tools at the same time. - -### Batch Update of PID constants -The CLI only supports setting one PID constant at a time using the following command. - -From the `groundStation` folder: -``` -./Cli setpid --pitch -p 1.000 +```bash + ./getnodes ``` -This can get tedious for 27 PID constants. +This will fetch the `block_id`, `type_id` and name of every node in the current graph -To help, we made a batch script that allows you to easily set all 27 PID constants at once and save your progress as you go. - -First, edit the `parameters.txt` file in the `groundStation/scripts` folder to specify the values you want to set. The script will parse this file and pass them to the `Cli` program. - -Then simply run the script from the `groundStation` folder: -``` -scripts/setpid_batch.sh -``` +You can run any number of any combination of frontend tools at the same time. +If you find it helpful, with this setup you can create a bash script that simply +runs the same commands. This has been found to be of use when we are tuning. -Remember to commit your changes in the `parameters.txt` file if you believe you have found a better default state for the quad. \ No newline at end of file +There are a couple of already written bash scripts in the `scripts/` folder. \ No newline at end of file diff --git a/groundStation/scripts/parameterize.sh b/groundStation/scripts/parameterize.sh index 591656810626bb7867698124adb50f46bc5e6579..9554cc5d7af53de49e1612e0766f3bb85b8d49b9 100755 --- a/groundStation/scripts/parameterize.sh +++ b/groundStation/scripts/parameterize.sh @@ -1,10 +1,9 @@ -cd .. -./addnode 0 "Zero" -./setparam "zero" 0 0 -./setsource "signal mixer" "pitch" "zero" 0 -./setsource "signal mixer" "roll" "zero" 0 -./setsource "signal mixer" "yaw" "zero" 0 -./addnode 0 "PWM_VAL" -./setparam "pwm_val" 0 100000 -./setsource "signal mixer" "throttle" "pwm_val" 0 +./setparam 'x pos pid' 0 -0.015 +./setparam 'x pos pid' 1 -0.0075 +./setparam 'x pos pid' 2 -0.08 +./setparam 'x pos pid' 3 0.94 +./setparam 'y pos pid' 0 0.015 +./setparam 'y pos pid' 1 0.0075 +./setparam 'y pos pid' 2 0.08 +./setparam 'y pos pid' 3 0.94 diff --git a/groundStation/scripts/touch_down.sh b/groundStation/scripts/touch_down.sh index 79a4bc11dc49dce027e4438eae05aa819b512c78..7098126f21074c3c534097fcc391eee352ea3a7a 100755 --- a/groundStation/scripts/touch_down.sh +++ b/groundStation/scripts/touch_down.sh @@ -1,6 +1,6 @@ #! /bin/bash -cut_off="-0.15" +cut_off="-0.17" regex='[+-]?[0-9]+\.?[0-9]*$' diff --git a/groundStation/src/backend/backend.c b/groundStation/src/backend/backend.c index f384a6a1a96f59985fabe29fa4a431678727b31a..cad01ff742bd0541e33089e7483411bce4cdb22e 100644 --- a/groundStation/src/backend/backend.c +++ b/groundStation/src/backend/backend.c @@ -103,7 +103,8 @@ struct timeval timeArr[MAX_HASH_SIZE]; // global variables static volatile int keepRunning = 1; -const char *TRACKER_IP = "UAV@192.168.0.120:3883"; +//const char *TRACKER_IP = "UAV@192.168.0.120:3883"; // If using 3050 lab computer to run vrpn +const char *TRACKER_IP = "UAV@192.168.0.194:3883"; // If using Eric's old laptop to run vrpn static int zyboSocket; static int backendSocket; struct ucart_vrpn_tracker * tracker = NULL; diff --git a/groundStation/src/cli/README.md b/groundStation/src/cli/README.md deleted file mode 100644 index ec546d4539dad7a4ce07116010e85a707ab4ef61..0000000000000000000000000000000000000000 --- a/groundStation/src/cli/README.md +++ /dev/null @@ -1,7 +0,0 @@ -# CLI - -## Usage - -The Cli has been designed to function similarly to command line programs. Run the program using ./Cli - -To run a specific command in the diff --git a/quad/src/gen_diagram/network.dot b/quad/src/gen_diagram/network.dot index 07cb977d796610ef9c22de4c76891b48fee1514f..401acb652fdf093d6198c64d26ffa37061e16f49 100644 --- a/quad/src/gen_diagram/network.dot +++ b/quad/src/gen_diagram/network.dot @@ -3,18 +3,18 @@ rankdir="LR" "Roll PID"[shape=record label="<f0>Roll PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=35.000] |<f5> [Ki=0.000] |<f6> [Kd=1.000] |<f7> [alpha=0.880]"] "Roll" -> "Roll PID":f1 [label="Constant"] -"Yaw Correction" -> "Roll PID":f2 [label="Rotated Y"] +"RC Roll" -> "Roll PID":f2 [label="Constant"] "Ts_IMU" -> "Roll PID":f3 [label="Constant"] "Pitch PID"[shape=record label="<f0>Pitch PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=35.000] |<f5> [Ki=0.000] |<f6> [Kd=1.000] |<f7> [alpha=0.880]"] "Pitch trim add" -> "Pitch PID":f1 [label="Sum"] -"Yaw Correction" -> "Pitch PID":f2 [label="Rotated X"] +"RC Pitch" -> "Pitch PID":f2 [label="Constant"] "Ts_IMU" -> "Pitch PID":f3 [label="Constant"] "Yaw PID"[shape=record label="<f0>Yaw PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=2.600] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] -"Yaw" -> "Yaw PID":f1 [label="Constant"] +"PSI Sum" -> "Yaw PID":f1 [label="Sum"] "Yaw Setpoint" -> "Yaw PID":f2 [label="Constant"] -"Ts_VRPN" -> "Yaw PID":f3 [label="Constant"] +"Ts_IMU" -> "Yaw PID":f3 [label="Constant"] "Roll Rate PID"[shape=record label="<f0>Roll Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.030] |<f5> [Ki=0.000] |<f6> [Kd=0.005] |<f7> [alpha=0.880]"] "Gyro X" -> "Roll Rate PID":f1 [label="Constant"] @@ -28,23 +28,23 @@ label="<f0>Pitch Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt | "Yaw Rate PID"[shape=record label="<f0>Yaw Rate PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.297] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] "Gyro Z" -> "Yaw Rate PID":f1 [label="Constant"] -"Yaw PID" -> "Yaw Rate PID":f2 [label="Correction"] +"RC Yaw" -> "Yaw Rate PID":f2 [label="Constant"] "Ts_IMU" -> "Yaw Rate PID":f3 [label="Constant"] "X pos PID"[shape=record label="<f0>X pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.550] |<f5> [Ki=0.007] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] -"VRPN X" -> "X pos PID":f1 [label="Constant"] +"OF X Trim Add" -> "X pos PID":f1 [label="Sum"] "X Setpoint" -> "X pos PID":f2 [label="Constant"] -"Ts_VRPN" -> "X pos PID":f3 [label="Constant"] +"Ts_IMU" -> "X pos PID":f3 [label="Constant"] "Y pos PID"[shape=record label="<f0>Y pos PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.550] |<f5> [Ki=0.007] |<f6> [Kd=0.000] |<f7> [alpha=0.000]"] -"VRPN Y" -> "Y pos PID":f1 [label="Constant"] +"OF Y Trim Add" -> "Y pos PID":f1 [label="Sum"] "Y Setpoint" -> "Y pos PID":f2 [label="Constant"] -"Ts_VRPN" -> "Y pos PID":f3 [label="Constant"] +"Ts_IMU" -> "Y pos PID":f3 [label="Constant"] "Altitude PID"[shape=record label="<f0>Altitude PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=-0.098] |<f5> [Ki=-0.008] |<f6> [Kd=-0.074] |<f7> [alpha=0.880]"] -"VRPN Alt" -> "Altitude PID":f1 [label="Constant"] +"Lidar" -> "Altitude PID":f1 [label="Constant"] "Alt Setpoint" -> "Altitude PID":f2 [label="Constant"] -"Ts_VRPN" -> "Altitude PID":f3 [label="Constant"] +"Ts_IMU" -> "Altitude PID":f3 [label="Constant"] "X Setpoint"[shape=record label="<f0>X Setpoint |<f1> [Constant=0.000]"] "Y Setpoint"[shape=record @@ -71,6 +71,10 @@ label="<f0>Lidar |<f1> [Constant=0.000]"] label="<f0>Flow Vel X |<f1> [Constant=0.000]"] "Flow Vel Y"[shape=record label="<f0>Flow Vel Y |<f1> [Constant=0.000]"] +"Flow Vel X Filt"[shape=record +label="<f0>Flow Vel X Filt |<f1> [Constant=0.000]"] +"Flow Vel Y Filt"[shape=record +label="<f0>Flow Vel Y Filt |<f1> [Constant=0.000]"] "Flow Quality"[shape=record label="<f0>Flow Quality |<f1> [Constant=0.000]"] "Flow Distance"[shape=record @@ -116,24 +120,18 @@ label="<f0>RC Yaw |<f1> [Constant=0.000]"] label="<f0>RC Throttle |<f1> [Constant=0.000]"] "X Vel PID"[shape=record label="<f0>X Vel PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=-0.100] |<f5> [Ki=0.000] |<f6> [Kd=-0.020] |<f7> [alpha=0.000]"] -"X Vel" -> "X Vel PID":f1 [label="Correction"] +"Flow Vel X Filt" -> "X Vel PID":f1 [label="Constant"] "X Vel Clamp" -> "X Vel PID":f2 [label="Bounded"] -"Ts_VRPN" -> "X Vel PID":f3 [label="Constant"] +"Ts_IMU" -> "X Vel PID":f3 [label="Constant"] "Y Vel PID"[shape=record label="<f0>Y Vel PID |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.100] |<f5> [Ki=0.000] |<f6> [Kd=0.020] |<f7> [alpha=0.000]"] -"Y Vel" -> "Y Vel PID":f1 [label="Correction"] +"Flow Vel Y Filt" -> "Y Vel PID":f1 [label="Constant"] "Y vel Clamp" -> "Y Vel PID":f2 [label="Bounded"] -"Ts_VRPN" -> "Y Vel PID":f3 [label="Constant"] +"Ts_IMU" -> "Y Vel PID":f3 [label="Constant"] "X Vel"[shape=record -label="<f0>X Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=-1.000] |<f7> [alpha=0.880]"] -"VRPN X" -> "X Vel":f1 [label="Constant"] -"zero" -> "X Vel":f2 [label="Constant"] -"Ts_VRPN" -> "X Vel":f3 [label="Constant"] +label="<f0>X Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.880]"] "Y Vel"[shape=record -label="<f0>Y Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=-1.000] |<f7> [alpha=0.880]"] -"VRPN Y" -> "Y Vel":f1 [label="Constant"] -"zero" -> "Y Vel":f2 [label="Constant"] -"Ts_VRPN" -> "Y Vel":f3 [label="Constant"] +label="<f0>Y Vel |<f1> --\>Cur point |<f2> --\>Setpoint |<f3> --\>dt |<f4> [Kp=0.000] |<f5> [Ki=0.000] |<f6> [Kd=0.000] |<f7> [alpha=0.880]"] "X Vel Clamp"[shape=record label="<f0>X Vel Clamp |<f1> --\>Bounds in |<f2> [Min=-2.000] |<f3> [Max=2.000]"] "X pos PID" -> "X Vel Clamp":f1 [label="Correction"] @@ -142,20 +140,14 @@ label="<f0>Y vel Clamp |<f1> --\>Bounds in |<f2> [Min=-2.000] |<f3> [Max=2.000] "Y pos PID" -> "Y vel Clamp":f1 [label="Correction"] "Yaw Correction"[shape=record label="<f0>Yaw Correction |<f1> --\>Current Yaw |<f2> --\>X Position |<f3> --\>Y Position"] -"Yaw" -> "Yaw Correction":f1 [label="Constant"] +"PSI Sum" -> "Yaw Correction":f1 [label="Sum"] "X Vel PID" -> "Yaw Correction":f2 [label="Correction"] "Y Vel PID" -> "Yaw Correction":f3 [label="Correction"] "OF Offset Angle"[shape=record label="<f0>OF Offset Angle |<f1> --\>Current Yaw |<f2> --\>X Position |<f3> --\>Y Position"] -"OF Offset Add" -> "OF Offset Angle":f1 [label="Sum"] +"PSI Sum" -> "OF Offset Angle":f1 [label="Sum"] "Flow Vel X" -> "OF Offset Angle":f2 [label="Constant"] "Flow Vel Y" -> "OF Offset Angle":f3 [label="Constant"] -"OF Offset Rot"[shape=record -label="<f0>OF Offset Rot |<f1> [Constant=0.622]"] -"OF Offset Add"[shape=record -label="<f0>OF Offset Add |<f1> --\>Summand 1 |<f2> --\>Summand 2"] -"OF Offset Rot" -> "OF Offset Add":f1 [label="Constant"] -"Yaw" -> "OF Offset Add":f2 [label="Constant"] "OF Integrate X"[shape=record label="<f0>OF Integrate X |<f1> --\>Integrator In |<f2> --\>Integrator dt"] "OF Offset Angle" -> "OF Integrate X":f1 [label="Rotated X"] @@ -176,9 +168,29 @@ label="<f0>OF X Trim Add |<f1> --\>Summand 1 |<f2> --\>Summand 2"] label="<f0>OF Y Trim Add |<f1> --\>Summand 1 |<f2> --\>Summand 2"] "OF Integrate Y" -> "OF Y Trim Add":f1 [label="Integrated"] "OF Trim Y" -> "OF Y Trim Add":f2 [label="Constant"] +"PSI Dot"[shape=record +label="<f0>PSI Dot |<f1> [Constant=0.000]"] +"PSI Dot Offset"[shape=record +label="<f0>PSI Dot Offset |<f1> [Constant=0.000]"] +"PSI Dot Sum"[shape=record +label="<f0>PSI Dot Sum |<f1> --\>Summand 1 |<f2> --\>Summand 2"] +"PSI Dot" -> "PSI Dot Sum":f1 [label="Constant"] +"PSI Dot Offset" -> "PSI Dot Sum":f2 [label="Constant"] +"PSI Angle"[shape=record +label="<f0>PSI Angle |<f1> --\>Integrator In |<f2> --\>Integrator dt"] +"PSI Dot Sum" -> "PSI Angle":f1 [label="Sum"] +"Ts_IMU" -> "PSI Angle":f2 [label="Constant"] +"PSI Angle Offset"[shape=record +label="<f0>PSI Angle Offset |<f1> [Constant=0.000]"] +"PSI Sum"[shape=record +label="<f0>PSI Sum |<f1> --\>Summand 1 |<f2> --\>Summand 2"] +"PSI Angle" -> "PSI Sum":f1 [label="Integrated"] +"PSI Angle Offset" -> "PSI Sum":f2 [label="Constant"] +"Mag Yaw"[shape=record +label="<f0>Mag Yaw |<f1> [Constant=0.000]"] "Signal Mixer"[shape=record label="<f0>Signal Mixer |<f1> --\>Throttle |<f2> --\>Pitch |<f3> --\>Roll |<f4> --\>Yaw"] -"T trim add" -> "Signal Mixer":f1 [label="Sum"] +"RC Throttle" -> "Signal Mixer":f1 [label="Constant"] "P PWM Clamp" -> "Signal Mixer":f2 [label="Bounded"] "R PWM Clamp" -> "Signal Mixer":f3 [label="Bounded"] "Y PWM Clamp" -> "Signal Mixer":f4 [label="Bounded"] diff --git a/quad/src/gen_diagram/network.png b/quad/src/gen_diagram/network.png index f13041740aa8c01eec3c0d83b8ceaab251505c22..b45f77b3e859babf1d2aa3e249d765ca6b43eb49 100644 Binary files a/quad/src/gen_diagram/network.png and b/quad/src/gen_diagram/network.png differ diff --git a/quad/src/quad_app/control_algorithm.c b/quad/src/quad_app/control_algorithm.c index 624c0642abfd47bc4de3cc586d9226dca28fa2a6..be9e842eca61a528edad09b017a4fb44b7a4e71f 100644 --- a/quad/src/quad_app/control_algorithm.c +++ b/quad/src/quad_app/control_algorithm.c @@ -13,11 +13,15 @@ #include "util.h" #include "timer.h" -//#define USE_LIDAR -#define MAX_VALID_LIDAR (10.0) // Maximum valid distance to read from LiDAR to update +#define USE_LIDAR +#define USE_OF +#define USE_GYRO_YAW +#define NO_VRPN + +//10 degrees +#define ANGLE_CLAMP (0.1745) #define PX4FLOW_QUAL_MIN (100) -#define OF_OFFSET_ANGLE (0.62204) // 35.64 degrees #define ROLL_PITCH_MAX_ANGLE 0.35 // 20 degrees #define PWM_DIFF_BOUNDS 20000 @@ -29,8 +33,13 @@ void connect_autonomous(parameter_t* ps) { //graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->y_pos_pid, PID_CORRECTION); graph_set_source(graph, ps->pitch_pid, PID_SETPOINT, ps->yaw_correction, ROT_OUT_X); graph_set_source(graph, ps->roll_pid, PID_SETPOINT, ps->yaw_correction, ROT_OUT_Y); - graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->throttle_trim_add, ADD_SUM); graph_set_source(graph, ps->yaw_r_pid, PID_SETPOINT, ps->yaw_pid, PID_CORRECTION); +#ifdef USE_OF + //graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->rc_throttle, ADD_SUM); + graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->throttle_trim_add, ADD_SUM); +#else + graph_set_source(graph, ps->mixer, MIXER_THROTTLE, ps->throttle_trim_add, ADD_SUM); +#endif } void connect_manual(parameter_t* ps) { @@ -70,6 +79,8 @@ int control_algorithm_init(parameter_t * ps) ps->lidar = graph_add_defined_block(graph, BLOCK_CONSTANT, "Lidar"); ps->flow_vel_x = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Vel X"); ps->flow_vel_y = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Vel Y"); + ps->flow_vel_x_filt = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Vel X Filt"); + ps->flow_vel_y_filt = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Vel Y Filt"); ps->flow_quality = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Quality"); ps->flow_distance = graph_add_defined_block(graph, BLOCK_CONSTANT, "Flow Distance"); // Sensor trims @@ -109,8 +120,6 @@ int control_algorithm_init(parameter_t * ps) // Optical Flow ps->of_angle_corr = graph_add_defined_block(graph, BLOCK_YAW_ROT, "OF Offset Angle"); - ps->of_angle_offset = graph_add_defined_block(graph, BLOCK_CONSTANT, "OF Offset Rot"); - ps->of_angle_add = graph_add_defined_block(graph, BLOCK_ADD, "OF Offset Add"); ps->of_integ_x = graph_add_defined_block(graph, BLOCK_INTEGRATOR, "OF Integrate X"); ps->of_integ_y = graph_add_defined_block(graph, BLOCK_INTEGRATOR, "OF Integrate Y"); ps->of_trim_x = graph_add_defined_block(graph, BLOCK_CONSTANT, "OF Trim X"); @@ -118,6 +127,17 @@ int control_algorithm_init(parameter_t * ps) ps->of_trimmed_x = graph_add_defined_block(graph, BLOCK_ADD, "OF X Trim Add"); ps->of_trimmed_y = graph_add_defined_block(graph, BLOCK_ADD, "OF Y Trim Add"); + // psi dot integrator + ps->psi_dot = graph_add_defined_block(graph, BLOCK_CONSTANT, "PSI Dot"); + ps->psi_dot_offset = graph_add_defined_block(graph, BLOCK_CONSTANT, "PSI Dot Offset"); + ps->psi_dot_sum = graph_add_defined_block(graph, BLOCK_ADD, "PSI Dot Sum"); + ps->psi = graph_add_defined_block(graph, BLOCK_INTEGRATOR, "PSI Angle"); + ps->psi_offset = graph_add_defined_block(graph, BLOCK_CONSTANT, "PSI Angle Offset"); + ps->psi_sum = graph_add_defined_block(graph, BLOCK_ADD, "PSI Sum"); + + //Complementary yaw + ps->mag_yaw = graph_add_defined_block(graph, BLOCK_CONSTANT, "Mag Yaw"); + ps->mixer = graph_add_defined_block(graph, BLOCK_MIXER, "Signal Mixer"); ps->angle_time = graph_add_defined_block(graph, BLOCK_CONSTANT, "Ts_IMU"); @@ -152,6 +172,15 @@ int control_algorithm_init(parameter_t * ps) graph_set_source(graph, ps->yaw_r_pid, PID_CUR_POINT, ps->gyro_z, CONST_VAL); graph_set_source(graph, ps->yaw_r_pid, PID_DT, ps->angle_time, CONST_VAL); + //PSI-dot integration chain + graph_set_source(graph, ps->psi_dot_sum, ADD_SUMMAND1, ps->psi_dot, CONST_VAL); + graph_set_source(graph, ps->psi_dot_sum, ADD_SUMMAND2, ps->psi_dot_offset, CONST_VAL); + graph_set_source(graph, ps->psi, INTEGRATE_IN, ps->psi_dot_sum, CONST_VAL); + graph_set_source(graph, ps->psi, INTEGRATE_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->psi_sum, ADD_SUMMAND1, ps->psi, INTEGRATED); + graph_set_source(graph, ps->psi_sum, ADD_SUMMAND2, ps->psi_offset, CONST_VAL); + +#ifndef USE_OF // X velocity PID // Use a PID block to compute the derivative graph_set_param_val(graph, ps->x_vel, PID_KD, -1); @@ -161,15 +190,6 @@ int control_algorithm_init(parameter_t * ps) // Connect velocity PID itself graph_set_source(graph, ps->x_vel_pid, PID_DT, ps->pos_time, CONST_VAL); graph_set_source(graph, ps->x_vel_pid, PID_CUR_POINT, ps->x_vel, PID_CORRECTION); - //graph_set_source(graph, ps->x_vel_pid, PID_CUR_POINT, ps->of_angle_corr, ROT_OUT_X); - graph_set_source(graph, ps->x_vel_pid, PID_SETPOINT, ps->x_vel_clamp, BOUNDS_OUT); - graph_set_source(graph, ps->x_vel_clamp, BOUNDS_IN, ps->x_pos_pid, PID_CORRECTION); - - // X/Y global to local conversion - graph_set_source(graph, ps->yaw_correction, ROT_YAW, ps->cur_yaw, CONST_VAL); - graph_set_source(graph, ps->yaw_correction, ROT_CUR_X, ps->x_vel_pid, PID_CORRECTION); - graph_set_source(graph, ps->yaw_correction, ROT_CUR_Y, ps->y_vel_pid, PID_CORRECTION); - // Y velocity PID // Use a PID block to compute the derivative @@ -180,18 +200,48 @@ int control_algorithm_init(parameter_t * ps) // Connect velocity PID itself graph_set_source(graph, ps->y_vel_pid, PID_DT, ps->pos_time, CONST_VAL); graph_set_source(graph, ps->y_vel_pid, PID_CUR_POINT, ps->y_vel, PID_CORRECTION); - //graph_set_source(graph, ps->y_vel_pid, PID_CUR_POINT, ps->of_angle_corr, ROT_OUT_Y); - graph_set_source(graph, ps->y_vel_pid, PID_SETPOINT, ps->y_vel_clamp, BOUNDS_OUT); - graph_set_source(graph, ps->y_vel_clamp, BOUNDS_IN, ps->y_pos_pid, PID_CORRECTION); // X position graph_set_source(graph, ps->x_pos_pid, PID_DT, ps->pos_time, CONST_VAL); graph_set_source(graph, ps->x_pos_pid, PID_CUR_POINT, ps->vrpn_x, CONST_VAL); - //graph_set_source(graph, ps->x_pos_pid, PID_CUR_POINT, ps->of_trimmed_x, CONST_VAL); - graph_set_source(graph, ps->x_pos_pid, PID_SETPOINT, ps->x_set, CONST_VAL); + // Y position graph_set_source(graph, ps->y_pos_pid, PID_DT, ps->pos_time, CONST_VAL); graph_set_source(graph, ps->y_pos_pid, PID_CUR_POINT, ps->vrpn_y, CONST_VAL); +#else + // X position + graph_set_source(graph, ps->x_pos_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->x_pos_pid, PID_CUR_POINT, ps->of_trimmed_x, ADD_SUM); + + // Y position + graph_set_source(graph, ps->y_pos_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->y_pos_pid, PID_CUR_POINT, ps->of_trimmed_y, ADD_SUM); + + graph_set_source(graph, ps->x_vel_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->x_vel_pid, PID_CUR_POINT, ps->flow_vel_x_filt, PID_CORRECTION); + + graph_set_source(graph, ps->y_vel_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->y_vel_pid, PID_CUR_POINT, ps->flow_vel_y_filt, PID_CORRECTION); + +#endif + + graph_set_source(graph, ps->x_vel_pid, PID_SETPOINT, ps->x_vel_clamp, BOUNDS_OUT); + graph_set_source(graph, ps->x_vel_clamp, BOUNDS_IN, ps->x_pos_pid, PID_CORRECTION); + + // X/Y global to local conversion +#ifdef USE_GYRO_YAW + graph_set_source(graph, ps->yaw_correction, ROT_YAW, ps->psi_sum, ADD_SUM); +#else + graph_set_source(graph, ps->yaw_correction, ROT_YAW, ps->cur_yaw, CONST_VAL); +#endif + graph_set_source(graph, ps->yaw_correction, ROT_CUR_X, ps->x_vel_pid, PID_CORRECTION); + graph_set_source(graph, ps->yaw_correction, ROT_CUR_Y, ps->y_vel_pid, PID_CORRECTION); + + graph_set_source(graph, ps->y_vel_pid, PID_SETPOINT, ps->y_vel_clamp, BOUNDS_OUT); + graph_set_source(graph, ps->y_vel_clamp, BOUNDS_IN, ps->y_pos_pid, PID_CORRECTION); + + graph_set_source(graph, ps->x_pos_pid, PID_SETPOINT, ps->x_set, CONST_VAL); + //graph_set_source(graph, ps->y_pos_pid, PID_CUR_POINT, ps->of_trimmed_y, CONST_VAL); graph_set_source(graph, ps->y_pos_pid, PID_SETPOINT, ps->y_set, CONST_VAL); @@ -207,9 +257,14 @@ int control_algorithm_init(parameter_t * ps) graph_set_source(graph, ps->throttle_trim_add, ADD_SUMMAND1, ps->alt_pid, PID_CORRECTION); graph_set_source(graph, ps->throttle_trim_add, ADD_SUMMAND2, ps->throttle_trim, CONST_VAL); // Yaw angle +#ifdef USE_GYRO_YAW + graph_set_source(graph, ps->yaw_pid, PID_DT, ps->angle_time, CONST_VAL); + graph_set_source(graph, ps->yaw_pid, PID_CUR_POINT, ps->psi_sum, ADD_SUM); +#else graph_set_source(graph, ps->yaw_pid, PID_DT, ps->pos_time, CONST_VAL); - graph_set_source(graph, ps->yaw_pid, PID_SETPOINT, ps->yaw_set, CONST_VAL); graph_set_source(graph, ps->yaw_pid, PID_CUR_POINT, ps->cur_yaw, CONST_VAL); +#endif + graph_set_source(graph, ps->yaw_pid, PID_SETPOINT, ps->yaw_set, CONST_VAL); // Connect PWM clamping blocks graph_set_source(graph, ps->clamp_d_pwmP, BOUNDS_IN, ps->pitch_r_pid, PID_CORRECTION); @@ -223,9 +278,11 @@ int control_algorithm_init(parameter_t * ps) graph_set_source(graph, ps->mixer, MIXER_YAW, ps->clamp_d_pwmY, BOUNDS_OUT); // Connect optical flow - graph_set_source(graph, ps->of_angle_add, ADD_SUMMAND1, ps->of_angle_offset, CONST_VAL); - graph_set_source(graph, ps->of_angle_add, ADD_SUMMAND2, ps->cur_yaw, CONST_VAL); - graph_set_source(graph, ps->of_angle_corr, ROT_YAW, ps->of_angle_add, ADD_SUM); +#ifdef USE_GYRO_YAW + graph_set_source(graph, ps->of_angle_corr, ROT_YAW, ps->psi_sum, ADD_SUM); +#else + graph_set_source(graph, ps->of_angle_corr, ROT_YAW, ps->cur_yaw, ADD_SUM); +#endif graph_set_source(graph, ps->of_angle_corr, ROT_CUR_X, ps->flow_vel_x, CONST_VAL); graph_set_source(graph, ps->of_angle_corr, ROT_CUR_Y, ps->flow_vel_y, CONST_VAL); // Integration @@ -307,7 +364,6 @@ int control_algorithm_init(parameter_t * ps) // Set trims graph_set_param_val(graph, ps->pitch_trim, CONST_SET, PITCH_TRIM); - graph_set_param_val(graph, ps->of_angle_offset, CONST_SET, OF_OFFSET_ANGLE); // Initial value for sampling periods graph_set_param_val(graph, ps->pos_time, CONST_SET, 0.04); @@ -338,7 +394,11 @@ int control_algorithm_init(parameter_t * ps) // flap switch was just toggled to auto flight mode if((last_fm_switch != cur_fm_switch) && (cur_fm_switch == AUTO_FLIGHT_MODE)) { +#ifdef NO_VRPN + user_defined_struct->engaging_auto = 2; +#else user_defined_struct->engaging_auto = 1; +#endif graph_set_param_val(graph, ps->throttle_trim, CONST_SET, user_input_struct->rc_commands[THROTTLE]); } @@ -354,10 +414,17 @@ int control_algorithm_init(parameter_t * ps) // also reset the previous error and accumulated error from the position PIDs if((cur_fm_switch == AUTO_FLIGHT_MODE) && (user_defined_struct->engaging_auto == 2)) { +#ifdef USE_OF + graph_set_param_val(graph, ps->x_set, CONST_SET, graph_get_output(graph, ps->of_trimmed_x, ADD_SUM)); + graph_set_param_val(graph, ps->y_set, CONST_SET, graph_get_output(graph, ps->of_trimmed_y, ADD_SUM)); + //graph_set_param_val(graph, ps->alt_set, CONST_SET, sensor_struct->currentQuadPosition.alt_pos); + graph_set_param_val(graph, ps->yaw_set, CONST_SET, sensor_struct->currentQuadPosition.yaw); +#else graph_set_param_val(graph, ps->x_set, CONST_SET, sensor_struct->currentQuadPosition.x_pos); graph_set_param_val(graph, ps->y_set, CONST_SET, sensor_struct->currentQuadPosition.y_pos); graph_set_param_val(graph, ps->alt_set, CONST_SET, sensor_struct->currentQuadPosition.alt_pos); graph_set_param_val(graph, ps->yaw_set, CONST_SET, sensor_struct->currentQuadPosition.yaw); +#endif // reset the flag that engages auto mode user_defined_struct->engaging_auto = 0; @@ -399,19 +466,20 @@ int control_algorithm_init(parameter_t * ps) // Sensor values graph_set_param_val(graph, ps->cur_pitch, CONST_SET, sensor_struct->pitch_angle_filtered); graph_set_param_val(graph, ps->cur_roll, CONST_SET, sensor_struct->roll_angle_filtered); + graph_set_param_val(graph, ps->mag_yaw, CONST_SET, sensor_struct->yaw_angle_filtered); graph_set_param_val(graph, ps->gyro_y, CONST_SET, sensor_struct->gyr_y); graph_set_param_val(graph, ps->gyro_x, CONST_SET, sensor_struct->gyr_x); graph_set_param_val(graph, ps->gyro_z, CONST_SET, sensor_struct->gyr_z); - //if (fabs(sensor_struct->lidar_altitude) <= MAX_VALID_LIDAR) { - graph_set_param_val(graph, ps->lidar, CONST_SET, sensor_struct->lidar_altitude); - //} + graph_set_param_val(graph, ps->psi_dot, CONST_SET, sensor_struct->psi_dot); + graph_set_param_val(graph, ps->lidar, CONST_SET, sensor_struct->lidar_altitude); graph_set_param_val(graph, ps->flow_quality, CONST_SET, sensor_struct->optical_flow.quality); - //As per documentation, disregard frames with low quality, as they contain unreliable data - if (sensor_struct->optical_flow.quality >= PX4FLOW_QUAL_MIN) { - graph_set_param_val(graph, ps->flow_vel_x, CONST_SET, sensor_struct->optical_flow.xVel); - graph_set_param_val(graph, ps->flow_vel_y, CONST_SET, sensor_struct->optical_flow.yVel); - } + + //Optical flow + graph_set_param_val(graph, ps->flow_vel_x, CONST_SET, sensor_struct->optical_flow.xVel); + graph_set_param_val(graph, ps->flow_vel_y, CONST_SET, sensor_struct->optical_flow.yVel); graph_set_param_val(graph, ps->flow_distance, CONST_SET, sensor_struct->optical_flow.distance); + graph_set_param_val(graph, ps->flow_vel_x_filt, CONST_SET, sensor_struct->optical_flow.xVelFilt); + graph_set_param_val(graph, ps->flow_vel_y_filt, CONST_SET, sensor_struct->optical_flow.yVelFilt); // RC values graph_set_param_val(graph, ps->rc_pitch, CONST_SET, user_input_struct->pitch_angle_manual_setpoint); diff --git a/quad/src/quad_app/log_data.c b/quad/src/quad_app/log_data.c index 2a29ddb8f798a1e9a80dfe6c879e196358621f67..7079987a54d2288970d34af671f41d8b06e2cafd 100644 --- a/quad/src/quad_app/log_data.c +++ b/quad/src/quad_app/log_data.c @@ -118,11 +118,11 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { addOutputToLog(log_struct, ps->of_angle_corr, ROT_OUT_Y, m_s); addOutputToLog(log_struct, ps->of_integ_x, INTEGRATED, m); addOutputToLog(log_struct, ps->of_integ_y, INTEGRATED, m); + addOutputToLog(log_struct, ps->psi_sum, ADD_SUM, rad); + addOutputToLog(log_struct, ps->mag_yaw, CONST_VAL, rad); addParamToLog(log_struct, ps->cur_roll, CONST_VAL, rad); addParamToLog(log_struct, ps->cur_yaw, CONST_VAL, rad); - addParamToLog(log_struct, ps->vrpn_pitch, CONST_VAL, rad); - addParamToLog(log_struct, ps->vrpn_roll, CONST_VAL, rad); addParamToLog(log_struct, ps->x_set, CONST_VAL, m); addParamToLog(log_struct, ps->y_set, CONST_VAL, m); addParamToLog(log_struct, ps->alt_set, CONST_VAL, m); @@ -134,13 +134,9 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { addParamToLog(log_struct, ps->flow_vel_x, CONST_VAL, m_s); addParamToLog(log_struct, ps->flow_vel_y, CONST_VAL, m_s); addParamToLog(log_struct, ps->flow_quality, CONST_VAL, "none"); - addParamToLog(log_struct, ps->flow_distance, CONST_VAL, m); - addParamToLog(log_struct, ps->rc_throttle, CONST_VAL, pwm_val); - addParamToLog(log_struct, ps->rc_pitch, CONST_VAL, pwm_val); - addParamToLog(log_struct, ps->rc_roll, CONST_VAL, pwm_val); // TODO: Make this not stupid. Adding 6 for IMU and 1 for timestamp - row_size = n_outputs + n_params + 6 + 1; + row_size = n_outputs + n_params + 9 + 1; size_t needed_memory = sizeof(float) * row_size * LOG_STARTING_SIZE; logArray = malloc(needed_memory); if (!logArray) { // malloc failed @@ -150,7 +146,6 @@ void initialize_logging(log_t* log_struct, parameter_t* ps) { } } - int log_data(log_t* log_struct, parameter_t* ps) { if(arrayIndex >= arraySize) @@ -166,6 +161,10 @@ int log_data(log_t* log_struct, parameter_t* ps) thisRow[offset++] = log_struct->gam.gyro_xVel_p; thisRow[offset++] = log_struct->gam.gyro_yVel_q; thisRow[offset++] = log_struct->gam.gyro_zVel_r; + thisRow[offset++] = log_struct->gam.mag_x; + thisRow[offset++] = log_struct->gam.mag_y; + thisRow[offset++] = log_struct->gam.mag_z; + int i; for (i = 0; i < n_params; i++) { @@ -223,7 +222,7 @@ void printLogging(struct CommDriver *comm, log_t* log_struct, parameter_t* ps, r } // Header names for the pre-defined values - safe_sprintf_cat(&buf, "%%Time\taccel_x\taccel_y\taccel_z\tgyro_x\tgyro_y\tgyro_z"); + safe_sprintf_cat(&buf, "%%Time\taccel_x\taccel_y\taccel_z\tgyro_x\tgyro_y\tgyro_z\tmag_x\tmag_y\tmag_z"); // Print all the recorded block parameters for (i = 0; i < n_params; i++) { @@ -244,7 +243,7 @@ void printLogging(struct CommDriver *comm, log_t* log_struct, parameter_t* ps, r // Send units header buf.size = 0; - safe_sprintf_cat(&buf, "&s\tG\tG\tG\trad/s\trad/s\trad/s"); // The pre-defined ones + safe_sprintf_cat(&buf, "&s\tG\tG\tG\trad/s\trad/s\trad/s\tuT\tuT\tuT"); // The pre-defined ones safe_sprintf_cat(&buf, units_output.str); safe_sprintf_cat(&buf, units_param.str); safe_sprintf_cat(&buf, "\n"); diff --git a/quad/src/quad_app/sensor_processing.c b/quad/src/quad_app/sensor_processing.c index cdd5a8c347895ed6c557f37b4e72659a1af39ab3..8e09dc8200452051b265704b9d8375a179028aa6 100644 --- a/quad/src/quad_app/sensor_processing.c +++ b/quad/src/quad_app/sensor_processing.c @@ -14,6 +14,16 @@ #include <math.h> #define ALPHA 0.99 +#define YAW_ALPHA (0.995) +#define PX4FLOW_QUAL_MIN (100) +#define PX4FLOW_VEL_DECAY (0.99) + +#define MAG_OFFSET_X (-33.9844) +#define MAG_OFFSET_Y (40.4922) + +#define GYRO_Z_OFFSET (0.0073) + +#define MAX_VALID_LIDAR (10.0) // Maximum valid distance to read from LiDAR to update int sensor_processing_init(sensor_t* sensor_struct) { float a0 = 0.0200833310260; @@ -24,13 +34,24 @@ int sensor_processing_init(sensor_t* sensor_struct) { sensor_struct->accel_x_filt = filter_make_state(a0, a1, a2, b1, b2); sensor_struct->accel_y_filt = filter_make_state(a0, a1, a2, b1, b2); sensor_struct->accel_z_filt = filter_make_state(a0, a1, a2, b1, b2); - float vel_a0 = 0.0098; - float vel_a1 = 0.0195; - float vel_a2 = 0.0098; - float vel_b1 = -1.5816; - float vel_b2 = 0.6853; + + //1 Hert filter + float vel_a0 = 2.3921e-4; + float vel_a1 = 4.7841e-4; + float vel_a2 = 2.3921e-4; + float vel_b1 = -1.9381; + float vel_b2 = 0.9391; sensor_struct->flow_x_filt = filter_make_state(vel_a0, vel_a1, vel_a2, vel_b1, vel_b2); sensor_struct->flow_y_filt = filter_make_state(vel_a0, vel_a1, vel_a2, vel_b1, vel_b2); + + float mag_a0 = 2.3921e-4; + float mag_a1 = 4.7841e-4; + float mag_a2 = 2.3921e-4; + float mag_b1 = -1.9281; + float mag_b2 = 0.9391; + sensor_struct->mag_x_filt = filter_make_state(mag_a0, mag_a1, mag_a2, mag_b1, mag_b2); + sensor_struct->mag_y_filt = filter_make_state(mag_a0, mag_a1, mag_a2, mag_b1, mag_b2); + return 0; } @@ -43,8 +64,14 @@ static float focal_length_px = 16.0 / (4.0f * 6.0f) * 1000.0f; //original focal void flow_to_vel(px4flow_t* flow_data, double distance) { double loop_time = get_last_loop_time(); if (loop_time != 0) { - flow_data->xVel = distance * flow_data->flowX / focal_length_px / get_last_loop_time(); - flow_data->yVel = distance * flow_data->flowY / focal_length_px / get_last_loop_time(); + if(flow_data->quality > PX4FLOW_QUAL_MIN) { + flow_data->xVel = distance * flow_data->flowX / focal_length_px / loop_time; + flow_data->yVel = distance * flow_data->flowY / focal_length_px / loop_time; + } + else { + flow_data->xVel *= PX4FLOW_VEL_DECAY; + flow_data->yVel *= PX4FLOW_VEL_DECAY; + } } } @@ -122,10 +149,10 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se sensor_struct->optical_flow = raw_sensor_struct->optical_flow; flow_to_vel(&sensor_struct->optical_flow, raw_sensor_struct->lidar_distance_m); -// sensor_struct->optical_flow.xVel = biquad_execute(&sensor_struct->flow_x_filt, -sensor_struct->optical_flow.xVel); -// sensor_struct->optical_flow.yVel = biquad_execute(&sensor_struct->flow_y_filt, -sensor_struct->optical_flow.yVel); - sensor_struct->optical_flow.xVel *= -1; - sensor_struct->optical_flow.yVel *= -1; + + //Filter OF velocities + sensor_struct->optical_flow.xVelFilt = biquad_execute(&sensor_struct->flow_x_filt, sensor_struct->optical_flow.xVel); + sensor_struct->optical_flow.yVelFilt = biquad_execute(&sensor_struct->flow_y_filt, sensor_struct->optical_flow.yVel); /* * Altitude double complementary filter @@ -136,6 +163,10 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se static float last_lidar = 0; float this_lidar = -raw_sensor_struct->lidar_distance_m; + if(this_lidar < (-MAX_VALID_LIDAR)) { + this_lidar = filtered_alt; + } + // Acceleration in m/s without gravity float quad_z_accel = 9.8 * (accel_z + 1); filtered_vel = alt_alpha*(filtered_vel + quad_z_accel*get_last_loop_time()) + @@ -146,6 +177,15 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se last_lidar = this_lidar; sensor_struct->lidar_altitude = filtered_alt; + //Magnetometer filter + float magX_filt = biquad_execute(&sensor_struct->mag_x_filt, gam->mag_x - MAG_OFFSET_X); + float magY_filt = biquad_execute(&sensor_struct->mag_y_filt, gam->mag_y - MAG_OFFSET_Y); + float mag_yaw = atan2(-magY_filt, -magX_filt); + + //Heading complementary filter + sensor_struct->yaw_angle_filtered = YAW_ALPHA * (sensor_struct->yaw_angle_filtered + + (sensor_struct->psi_dot)*get_last_loop_time()) + (1. - YAW_ALPHA) * mag_yaw; + return 0; } diff --git a/quad/src/quad_app/type_def.h b/quad/src/quad_app/type_def.h index d5bd1d45e240dd71e06ac784fc4c75e8b4e406d0..7dc7eba1ae043ffc99d3e12d9ac1a362e50c502f 100644 --- a/quad/src/quad_app/type_def.h +++ b/quad/src/quad_app/type_def.h @@ -102,15 +102,18 @@ typedef struct gam { float accel_roll; float accel_pitch; - // MAG - //Xint16 raw_mag_x, raw_mag_y, raw_mag_z; - - float heading; // In degrees + //float heading; // In degrees float mag_x; //Magnetic north: ~50 uT float mag_y; float mag_z; + float magX_correction; + float magY_correction; + float magZ_correction; + + int magDRDYCount; + SensorError_t error; } gam_t; @@ -126,6 +129,8 @@ typedef struct px4flow { double flowX, flowY; + double xVelFilt, yVelFilt; + int16_t quality; SensorError_t error; @@ -303,6 +308,7 @@ typedef struct sensor { // Complementary filter outputs float pitch_angle_filtered; float roll_angle_filtered; + float yaw_angle_filtered; // Z-axis value obtained from LiDAR // Note that this is not distance, as our Z-axis points upwards. @@ -319,6 +325,8 @@ typedef struct sensor { struct biquadState accel_z_filt; struct biquadState flow_x_filt; struct biquadState flow_y_filt; + struct biquadState mag_x_filt; + struct biquadState mag_y_filt; // Information obtained from optical flow sensor px4flow_t optical_flow; @@ -361,6 +369,8 @@ typedef struct parameter_t { int lidar; int flow_vel_x; // optical flow int flow_vel_y; + int flow_vel_x_filt; + int flow_vel_y_filt; int flow_quality; // Quality value returned by optical flow sensor int flow_distance; // VRPN blocks @@ -404,14 +414,20 @@ typedef struct parameter_t { // Sensor processing int yaw_correction; int of_angle_corr; // Corrects for the optical flow mounting angle - int of_angle_offset; // Offset for optical flow angle - int of_angle_add; // Adds optical flow static offset to current yaw int of_integ_x; // Integrates the optical flow data int of_integ_y; int of_trim_x; // Trim value for optical flow integrated value int of_trim_y; int of_trimmed_x; // Trimmed optical flow integrated value (of_integ_x + of_trim_x) int of_trimmed_y; + //psi dot integration chain + int psi_dot; + int psi_dot_offset; + int psi_dot_sum; + int psi; + int psi_offset; + int psi_sum; + int mag_yaw; //Complementary filtered magnetometer/gyro yaw } parameter_t; /** diff --git a/quad/xsdk_workspace/real_quad/.cproject b/quad/xsdk_workspace/real_quad/.cproject index eff70df8bb1fb6819d306f20afe048666440a183..57f76856b0208ef5824dd1bc3f413b84b8f3c3cf 100644 --- a/quad/xsdk_workspace/real_quad/.cproject +++ b/quad/xsdk_workspace/real_quad/.cproject @@ -109,7 +109,7 @@ </tool> <tool id="xilinx.gnu.arm.c.toolchain.compiler.release.85270120" name="ARM gcc compiler" superClass="xilinx.gnu.arm.c.toolchain.compiler.release"> <option defaultValue="gnu.c.optimization.level.more" id="xilinx.gnu.compiler.option.optimization.level.515686013" name="Optimization Level" superClass="xilinx.gnu.compiler.option.optimization.level" valueType="enumerated"/> - <option id="xilinx.gnu.compiler.option.debugging.level.1121150517" name="Debug Level" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.none" valueType="enumerated"/> + <option id="xilinx.gnu.compiler.option.debugging.level.1121150517" name="Debug Level" superClass="xilinx.gnu.compiler.option.debugging.level" value="gnu.c.debugging.level.max" valueType="enumerated"/> <option id="xilinx.gnu.compiler.inferred.swplatform.includes.687694973" name="Software Platform Include Path" superClass="xilinx.gnu.compiler.inferred.swplatform.includes" valueType="includePath"> <listOptionValue builtIn="false" value="../../system_bsp/ps7_cortexa9_0/include"/> </option> diff --git a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c index da9ed7ffc6346f652d13391ae6acfd738171892b..31b68f49d66c93896cb02f9f17afa4fe37f4cb34 100644 --- a/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c +++ b/quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c @@ -13,6 +13,8 @@ #define MAG_READ_SIZE 6 #define MAG_BASE_ADDR 0x03 +#define MAG_DRDY_TIMEOUT (10) + #define RAD_TO_DEG 57.29578 #define DEG_TO_RAD 0.0174533 @@ -44,7 +46,7 @@ #define GYRO_X_BIAS 0.005f #define GYRO_Y_BIAS -0.014f -#define GYRO_Z_BIAS 0.045f +#define GYRO_Z_BIAS 0.0534//0.0541f #define ACCEL_X_BIAS 0.023f #define ACCEL_Y_BIAS 0.009f @@ -53,6 +55,7 @@ int mpu9150_write(struct I2CDriver *i2c, u8 register_addr, u8 data); int mpu9150_read(struct I2CDriver *i2c, u8* recv_buffer, u8 register_addr, int size); +int mpu9150_calc_mag_sensitivity(struct IMUDriver *self, gam_t *gam); int mpu9150_read_mag(struct IMUDriver *self, gam_t* gam); int mpu9150_read_gyro_accel(gam_t* gam); @@ -77,23 +80,57 @@ int zybo_imu_reset(struct IMUDriver *self, gam_t *gam) { // Enable I2C bypass for AUX I2C (Magnetometer) mpu9150_write(i2c, 0x37, 0x02); - // Setup Mag - mpu9150_write(i2c, 0x37, 0x02); //INT_PIN_CFG -- INT_LEVEL=0 ; INT_OPEN=0 ; LATCH_INT_EN=0 ; INT_RD_CLEAR=0 ; FSYNC_INT_LEVEL=0 ; FSYNC_INT_EN=0 ; I2C_BYPASS_EN=0 ; CLKOUT_EN=0 - usleep(100000); + //Calculate magnetometer sensitivities + mpu9150_calc_mag_sensitivity(self, gam); + + usleep(10000); + + //Enable single measurement mode + mpu9150_write(i2c, 0x0A, 0x00); + mpu9150_write(i2c, 0x0A, 0x01); + int i; - gam_t temp_gam; // Do about 20 reads to warm up the device for(i=0; i < 20; ++i){ - self->read(self, &temp_gam); + self->read(self, gam); usleep(1000); } return 0; } +int mpu9150_calc_mag_sensitivity(struct IMUDriver *self, gam_t *gam) { + u8 buf[3]; + u8 ASAX, ASAY, ASAZ; + + // Quickly read from the factory ROM to get correction coefficents + int status = mpu9150_write(self->i2c, 0x0A, 0x0F); + if(status != 0) { + return status; + } + + usleep(10000); + + // Read raw adjustment values + status = mpu9150_read(self->i2c, buf, 0x10,3); + if(status != 0) { + return status; + } + ASAX = buf[0]; + ASAY = buf[1]; + ASAZ = buf[2]; + + // Set the correction coefficients + gam->magX_correction = (ASAX-128)*0.5/128 + 1; + gam->magY_correction = (ASAY-128)*0.5/128 + 1; + gam->magZ_correction = (ASAZ-128)*0.5/128 + 1; + + return 0; +} + int zybo_imu_read(struct IMUDriver *self, gam_t *gam) { struct I2CDriver *i2c = self->i2c; i16 raw_accel_x, raw_accel_y, raw_accel_z; @@ -126,7 +163,7 @@ int zybo_imu_read(struct IMUDriver *self, gam_t *gam) { gam->gyro_zVel_r = ((gyro_z / GYRO_SENS) * DEG_TO_RAD) + GYRO_Z_BIAS; // Magnometer - //mpu9150_read_mag(self, gam); + mpu9150_read_mag(self, gam); return error; } @@ -174,56 +211,55 @@ int mpu9150_read(struct I2CDriver *i2c, u8* recv_buffer, u8 register_addr, int s int mpu9150_read_mag(struct IMUDriver *self, gam_t* gam){ - - static double magX_correction = -1, magY_correction, magZ_correction; - - struct I2CDriver *i2c = self->i2c; - - u8 mag_data[6]; - i16 raw_magX, raw_magY, raw_magZ; - - // Grab calibrations if not done already - if(magX_correction == -1){ - u8 buf[3]; - u8 ASAX, ASAY, ASAZ; - - // Quickly read from the factory ROM to get correction coefficents - mpu9150_write(i2c, 0x0A, 0x0F); - usleep(10000); - - // Read raw adjustment values - mpu9150_read(i2c, buf, 0x10,3); - ASAX = buf[0]; - ASAY = buf[1]; - ASAZ = buf[2]; - - // Set the correction coefficients - magX_correction = (ASAX-128)*0.5/128 + 1; - magY_correction = (ASAY-128)*0.5/128 + 1; - magZ_correction = (ASAZ-128)*0.5/128 + 1; - } - - // Set Mag to single read mode - mpu9150_write(i2c, 0x0A, 0x01); - usleep(10000); - mag_data[0] = 0; - - // Keep checking if data is ready before reading new mag data - while(mag_data[0] == 0x00){ - mpu9150_read(i2c, mag_data, 0x02, 1); - } - - // Get mag data - mpu9150_read(i2c, mag_data, 0x03, 6); - - raw_magX = (mag_data[1] << 8) | mag_data[0]; - raw_magY = (mag_data[3] << 8) | mag_data[2]; - raw_magZ = (mag_data[5] << 8) | mag_data[4]; - - // Set magnetometer data to output - gam->mag_x = raw_magX * magX_correction; - gam->mag_y = raw_magY * magY_correction; - gam->mag_z = raw_magZ * magZ_correction; - - return 0; + u8 mag_data[6]; + u8 mag_status; + i16 raw_magX, raw_magY, raw_magZ; + + int trigger = 0; + + int status = mpu9150_read(self->i2c, mag_data, 0x02, 1); + if(status != 0) { + return status; + } + + if(mag_data[0] & 0x01) { + // Get mag data + status = mpu9150_read(self->i2c, mag_data, 0x03, 6); + if(status != 0) { + return status; + } + + status = mpu9150_read(self->i2c, &mag_status, 0x09, 1); + if(status != 0) { + return status; + } + + raw_magX = (mag_data[1] << 8) | mag_data[0]; + raw_magY = (mag_data[3] << 8) | mag_data[2]; + raw_magZ = (mag_data[5] << 8) | mag_data[4]; + + // Set magnetometer data to output + gam->mag_x = raw_magX * gam->magX_correction; + gam->mag_y = raw_magY * gam->magY_correction; + gam->mag_z = raw_magZ * gam->magZ_correction; + + trigger = 1; + } + else { + gam->magDRDYCount++; + + if(gam->magDRDYCount > MAG_DRDY_TIMEOUT) { + gam->magDRDYCount = 0; + + trigger = 1; + } + } + + if(trigger) { + //Start next reading + mpu9150_write(self->i2c, 0x0A, 0x00); + mpu9150_write(self->i2c, 0x0A, 0x01); + } + + return 0; } diff --git a/quad/xsdk_workspace/real_quad/src/main.c b/quad/xsdk_workspace/real_quad/src/main.c index d715d8e6538906b99b38f21f50260d801540c4cf..198b48d057c468db94336fad51a42d6a5d7682ab 100644 --- a/quad/xsdk_workspace/real_quad/src/main.c +++ b/quad/xsdk_workspace/real_quad/src/main.c @@ -48,7 +48,7 @@ int main() #ifdef RUN_TESTS //test_zybo_mio7_led_and_system(); //test_zybo_i2c(); - //test_zybo_i2c_imu(); + test_zybo_i2c_imu(); //test_zybo_i2c_px4flow(); //test_zybo_i2c_lidar(); //test_zybo_i2c_all(); diff --git a/quad/xsdk_workspace/real_quad/test/.gitignore b/quad/xsdk_workspace/real_quad/test/.gitignore deleted file mode 100644 index f159545885dfb8a7708b4f411522df65889865cf..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/real_quad/test/.gitignore +++ /dev/null @@ -1 +0,0 @@ -test_uart_buff \ No newline at end of file diff --git a/quad/xsdk_workspace/real_quad/test/Makefile b/quad/xsdk_workspace/real_quad/test/Makefile deleted file mode 100644 index 36613e465ba609b8db63bacd290c279eee14825a..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/real_quad/test/Makefile +++ /dev/null @@ -1,10 +0,0 @@ -# QUAD_ROOT is obtained from environment -SRC = $(QUAD_ROOT)/sw/modular_quad_pid/src -LIB = $(QUAD_ROOT)/lib/test - -test_uart_buff: test_uart_buff.c - gcc -o test_uart_buff -I. -I$(SRC) -I$(LIB) $(LIB)/test.o test_uart_buff.c $(SRC)/uart_buff.c - -.PHONY: clean -clean: - rm test_uart_buff diff --git a/quad/xsdk_workspace/real_quad/test/test_uart_buff.c b/quad/xsdk_workspace/real_quad/test/test_uart_buff.c deleted file mode 100644 index db85a701aad5553496357954d8e0df4a6745388b..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/real_quad/test/test_uart_buff.c +++ /dev/null @@ -1,348 +0,0 @@ -#include <stdio.h> -#include "uart_buff.h" -#include <math.h> -#include <string.h> -#include "test.h" - -int float_equals(float x1, float x2) { - return fabs(x1 - x2) < 10e-5; -} - -void print_test_result(int success, float exp, float act) { - if (success) printf("passed\n"); - else printf("FAILED: expected %f but got %f\n", exp, act); -} - -int failed(char *msg) { - printf("%s\n", msg); - return 1; -} - -void add_packet(u16 type, unsigned short id, unsigned short length, unsigned char *data) { - uart_buff_add_u8(0xBE); - uart_buff_add_u8(type); - uart_buff_add_u8(type >> 8); - uart_buff_add_u8(id); - uart_buff_add_u8(id >> 8); - uart_buff_add_u8(length); - uart_buff_add_u8(length >> 8); - int i; - for (i = 0; i < length; i += 1) { - uart_buff_add_u8(data[i]); - } - // fake checksum - uart_buff_add_u8(1); -} - -void add_VRPN_packet() { - float arr[6] = {1.0, 1.2, 1.4, -1.5, -0.5, -1.1}; - unsigned char *data = (unsigned char *) &arr; - add_packet(4, 0, 24, data); -} - -void add_basic_packet() { - unsigned char data[6] = {0xAA, 0xBB, 0xCC, 0xDD, 0xEE, 0xFF}; - add_packet(4, 0, 6, data); -} - -void add_garbage_data() { - int i; - for (i = 0; i < 32; i += 1) { - uart_buff_add_u8(i); - } -} - - -int setup_VRPN_packet() { - add_VRPN_packet(); - if (!uart_buff_packet_ready()) { - return 0; - } -} - -int setup_basic_packet() { - add_basic_packet(); - if (!uart_buff_packet_ready()) { - return 0; - } -} - -int test_empty_when_empty() { - uart_buff_reset(); - int exp = 1; - int act = uart_buff_empty(); - int success = exp == act; - return !success; -} - -int test_empty_after_receiving_some_data() { - uart_buff_reset(); - add_garbage_data(); - int exp = 0; - int act = uart_buff_empty(); - int success = exp == act; - return !success; -} - -int test_full_is_false_at_start() { - uart_buff_reset(); - int exp = 0; - int act = uart_buff_full(); - int success = exp == act; - return !success; -} - -int test_full_after_receiving_some_data() { - uart_buff_reset(); - add_garbage_data(); - int exp = 0; - int act = uart_buff_full(); - int success = exp == act; - return !success; -} - -int test_buffer_size_empty() { - uart_buff_reset(); - int exp = 0; - int act = uart_buff_size(); - int success = exp == act; - return !success; -} - -int test_buffer_size_after_garbage_data() { - uart_buff_reset(); - add_garbage_data(); - int exp = 32; - int act = uart_buff_size(); - int success = exp == act; - return !success; -} - -int test_buffer_size_after_garbage_data_scanned() { - uart_buff_reset(); - add_garbage_data(); - uart_buff_packet_ready(); - int exp = 0; - int act = uart_buff_size(); - int success = exp == act; - return !success; -} - -int test_buffer_size_after_VRPN_packet() { - uart_buff_reset(); - if(!setup_VRPN_packet()) return failed("FAILED: setup failed"); - int exp = 32; - int act = uart_buff_size(); - int success = exp == act; - return !success; -} - -int test_packet_get_u8() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xAA; - int act = uart_buff_data_get_u8(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u8_with_offset() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xBB; - int act = uart_buff_data_get_u8(1); - int success = exp == act; - return !success; -} - -int test_packet_get_u16() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xBBAA; - int act = uart_buff_data_get_u16(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u16_with_offset() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xDDCC; - int act = uart_buff_data_get_u16(2); - int success = exp == act; - return !success; -} - -int test_packet_get_u16_wrapped() { - uart_buff_reset(); - int i; - for (i = 0; i < 1000; i += 1) uart_buff_add_u8(0); - uart_buff_packet_ready(); - for (i = 0; i < 1040; i += 1) uart_buff_add_u8(0); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xBBAA; - int act = uart_buff_data_get_u16(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u32() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - unsigned int exp = 0xDDCCBBAA; - unsigned int act = uart_buff_data_get_u32(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u32_with_offset() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - unsigned int exp = 0xFFEEDDCC; - unsigned int act = uart_buff_data_get_u32(2); - int success = exp == act; - return !success; -} - -int test_packet_get_u32_wrapped_1_4() { - uart_buff_reset(); - int i; - for (i = 0; i < 1000; i += 1) uart_buff_add_u8(0); - uart_buff_packet_ready(); - for (i = 0; i < 1040; i += 1) uart_buff_add_u8(0); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xDDCCBBAA; - int act = uart_buff_data_get_u32(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u32_wrapped_2_4() { - uart_buff_reset(); - int i; - for (i = 0; i < 1000; i += 1) uart_buff_add_u8(0); - uart_buff_packet_ready(); - for (i = 0; i < 1039; i += 1) uart_buff_add_u8(0); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xDDCCBBAA; - int act = uart_buff_data_get_u32(0); - int success = exp == act; - return !success; -} - -int test_packet_get_u32_wrapped_3_4() { - uart_buff_reset(); - int i; - for (i = 0; i < 1000; i += 1) uart_buff_add_u8(0); - uart_buff_packet_ready(); - for (i = 0; i < 1038; i += 1) uart_buff_add_u8(0); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 0xDDCCBBAA; - int act = uart_buff_data_get_u32(0); - int success = exp == act; - return !success; -} - - -int test_packet_get_float() { - uart_buff_reset(); - if(!setup_VRPN_packet()) return failed("FAILED: setup failed"); - float exp = 1.0; - float act = uart_buff_data_get_float(0); - int success = float_equals(exp, act); - return !success; -} - -int test_packet_get_float_with_offset() { - uart_buff_reset(); - if(!setup_VRPN_packet()) return failed("FAILED: setup failed"); - float exp = 1.2; - float act = uart_buff_data_get_float(4); - int success = float_equals(exp, act); - return !success; -} - -int test_packet_ready_at_start() { - uart_buff_reset(); - int exp = 0; - int act = uart_buff_packet_ready(); - int success = act == exp; - return !success; -} - -int test_packet_ready_after_receiving_packet() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - int exp = 1; - int act = uart_buff_packet_ready(); - int success = act == exp; - return !success; -} - -int test_packet_ready_after_consuming_packet() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - uart_buff_consume_packet(); - int exp = 0; - int act = uart_buff_packet_ready(); - int success = act == exp; - return !success; -} - -int test_size_when_data_lenth_too_large() { - uart_buff_reset(); - unsigned char data[UART_MAX_PACKET_SIZE + 1]; - add_packet(4, 0, UART_MAX_PACKET_SIZE + 1, data); - uart_buff_packet_ready(); - int exp = 0; - int act = uart_buff_size(); - int success = act == exp; - return !success; -} - -int test_get_raw() { - uart_buff_reset(); - if(!setup_basic_packet()) return failed("FAILED: setup failed"); - unsigned char exp[15] = - {0xBE, 0x04, 0x00, 0x00, 0x00, 0x06, 0x00, 0xAA, 0xBB, 0xCC, 0xDD, 0xEE, 0xFF, 0x01}; - size_t length; - unsigned char *act = (unsigned char *) uart_buff_get_raw(&length); - int success = 1; - int i; - for (i = 0; i < length; i += 1) { - success = success && (exp[i] == act[i]); - if (!success) { - break; - } - } - return !success; -} - -int main() { - test(test_empty_when_empty, "test empty when empty"); - test(test_empty_after_receiving_some_data, "test empty after recieving soem data"); - test(test_full_is_false_at_start, "test full is false at start"); - test(test_full_after_receiving_some_data, "test full after receiving some data"); - test(test_packet_get_u8, "test packet get u8"); - test(test_packet_get_u8_with_offset, "test packet get u8 with offset"); - test(test_packet_get_u16, "test packet get u16"); - test(test_packet_get_u16_with_offset, "test packet get u16 wrapped"); - test(test_packet_get_u16_wrapped, "test packet get u16 wrapped"); - test(test_packet_get_u32, "test packet get u32"); - test(test_packet_get_u32_with_offset, "test packet get u32 with offset"); - test(test_packet_get_u32_wrapped_1_4, "test packet get u32 wrapped 1/4"); - test(test_packet_get_u32_wrapped_2_4, "test packet get u32 warpped 2/4"); - test(test_packet_get_u32_wrapped_3_4, "test packet get u32 wrapped 3/4"); - test(test_packet_get_float, "test packet get u32 wrapped 3/4"); - test(test_packet_get_float_with_offset, "test packet get float with offset"); - test(test_buffer_size_after_VRPN_packet, "test buffer size after VRPN packet"); - test(test_buffer_size_empty, "test buffer size empty"); - test(test_buffer_size_after_garbage_data, "test buffer size after garbage data"); - test(test_buffer_size_after_garbage_data_scanned, "test buffer size after garbage data scanned"); - test(test_packet_ready_at_start, "test packet ready at start"); - test(test_packet_ready_after_receiving_packet, "test packet ready after receiving packet"); - test(test_packet_ready_after_consuming_packet, "test packet ready after consuming packet"); - test(test_size_when_data_lenth_too_large, "test size when data length too large"); - - return test_summary(); -} diff --git a/quad/xsdk_workspace/real_quad/test/xil_types.h b/quad/xsdk_workspace/real_quad/test/xil_types.h deleted file mode 100644 index d67aef849b6b14143b6f19692c5dc33370b804e2..0000000000000000000000000000000000000000 --- a/quad/xsdk_workspace/real_quad/test/xil_types.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef XIL_TYPES_H -#define XIL_TYPES_H - -#include <stddef.h> - -typedef unsigned char u8; -typedef unsigned short u16; -typedef unsigned int u32; - -#endif diff --git a/website/.gitignore b/website/.gitignore index e5d0254d0bd444bbc69f6ba4626b945b2bd724ab..8b63161329bb240e4cd1fb6495ba34d2ca1da42a 100644 --- a/website/.gitignore +++ b/website/.gitignore @@ -1,5 +1,6 @@ output/ PASSWORD +TEAM lib/python2.7/site-packages/ pelicanconf.pyc *.pyc diff --git a/website/README.md b/website/README.md index ee88e06ca4f9764e2c1ed8be5a628b0cbb200ad6..0f116023b6615da096687dd5ae905619fe5bfb54 100644 --- a/website/README.md +++ b/website/README.md @@ -1,5 +1,4 @@ -Contributing ----- +# Making Changes to the Website ## Setup Environment @@ -32,8 +31,14 @@ make build ## Deploying the website -To deploy the website to our domain `may1716.sd.ece.iastate.edu`: +Before deploying, ensure you have 2 files in the website root directory: the +`PASSWORD` file and the `TEAM` file. The `PASSWORD` file should contain the sftp +password that was emailed to you for your website. The `TEAM` file should contain +the team name, something like `mayXXXX` or `decXXXX`. +The `PASSWORD` and `TEAM` files should contain NO SPACES and NO NEWLINES. + +When ready to deploy: ``` make deploy ``` diff --git a/website/content/computation_graph.md b/website/content/computation_graph.md index 0f955b19ceea85b6bb1455477a75aee37b5b00a4..a1c366601e9ff274cbd972dba73772c2b0ade07e 100644 --- a/website/content/computation_graph.md +++ b/website/content/computation_graph.md @@ -4,7 +4,7 @@ Authors: Brendan Category: Highlights thumbnail: "/images/computation_graph.png" -The controls team wants to start tuning the controller on the quadcopter, they also want to have the modify the controller in order to better characterize each part. Currently, there is no way to do that except re-write the code on the quad, which bleeds into their development cycle. David took the challenge to solve this issue, and developed the idea of a computation graph. +The controls team wants to start tuning the controller on the quadcopter; they also want to have the ability to modify the controller in order to better characterize each part. Currently, there is no way to do that except to re-write the code on the quad, which bleeds into their development cycle. David took the challenge to solve this issue, and developed the idea of a computation graph. <a href="/images/computation_graph.png"> <figure> diff --git a/website/content/files/492FinalReport.pdf b/website/content/files/492FinalReport.pdf new file mode 100644 index 0000000000000000000000000000000000000000..6a0264d9736ce63f87ca3f212bbaace41979f4da Binary files /dev/null and b/website/content/files/492FinalReport.pdf differ diff --git a/website/content/files/Poster.pdf b/website/content/files/Poster.pdf new file mode 100644 index 0000000000000000000000000000000000000000..9986215a5a1bb63e9a33ad7c92b25c5e6d6beb65 Binary files /dev/null and b/website/content/files/Poster.pdf differ diff --git a/website/content/pages/documents.md b/website/content/pages/documents.md index 26e6e6b37d8a52dacb5dab80fb95313a320b1057..f0ef4ccfd9ec5a3031a86fca913cd276b7886db6 100644 --- a/website/content/pages/documents.md +++ b/website/content/pages/documents.md @@ -13,6 +13,14 @@ sortorder: 005 [Design Document 1](/files/DesignDocument1.docx.pdf) [Design Document 2](/files/DesignDocument2.pdf) +## Final Report + +[Final Report](/files/492FinalReport.pdf) + +## Poster + +[Poster](/files/Poster.pdf) + ## Weekly Reports <iframe src="https://drive.google.com/embeddedfolderview?id=0BywzM7Q_7PUSeF8tdWpmMVN0eG8#list" width="100%" height="500" frameborder="0"></iframe> diff --git a/website/scripts/deploy.sh b/website/scripts/deploy.sh index f3902dd5305a912393e375c5999ce649addbe5ee..caffc9f4a86c8f78380feadc28102cfa675566e5 100644 --- a/website/scripts/deploy.sh +++ b/website/scripts/deploy.sh @@ -1,24 +1,27 @@ #!/bin/bash -HOST=may1716.sd.ece.iastate.edu -USERNAME=may1716 -if [ ! -e PASSWORD ]; then +if [ ! -e PASSWORD ] || [ ! -e TEAM ]; then echo " ***** -ERROR: File PASSWORD is missing. -Create a file called PASSWORD in the website root directory, and put the sftp -password in that file. No spaces. No newlines. +ERROR: File PASSWORD or file TEAM is missing. +Create 2 files in the website root directory, one named PASSWORD and another +named TEAM, and put the sftp password and senior design team name in these +files, respectively. No spaces. No newlines. (The SFTP password was given to us in an email. Just search 'sftp password' in -your CyMail and it will probably be first result.) +your CyMail and it will probably be first result. The senior design team +name is something like mayXXXX or decXXXX) ***** " exit 1 fi +TEAM=$(cat TEAM) PASSWORD=$(cat PASSWORD) +HOST=$TEAM.sd.ece.iastate.edu +USERNAME=$TEAM chmod -R 755 output || exit 1 #cd output || exit 1