Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
M
MicroCART
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Model registry
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Distributed Autonomous Networked Control Lab
MicroCART
Commits
2bf20b5c
Commit
2bf20b5c
authored
7 years ago
by
dawehr
Browse files
Options
Downloads
Patches
Plain Diff
Added lidar complementary filter and updated accelerometer Z bias.
parent
d60371f2
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
quad/src/quad_app/sensor_processing.c
+20
-2
20 additions, 2 deletions
quad/src/quad_app/sensor_processing.c
quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c
+1
-1
1 addition, 1 deletion
quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c
with
21 additions
and
3 deletions
quad/src/quad_app/sensor_processing.c
+
20
−
2
View file @
2bf20b5c
...
...
@@ -112,9 +112,8 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se
sensor_struct
->
roll_angle_filtered
=
ALPHA
*
(
sensor_struct
->
roll_angle_filtered
+
sensor_struct
->
phi_dot
*
get_last_loop_time
())
+
(
1
.
-
ALPHA
)
*
accel_roll
;
// Z-axis points upward, so negate distance
sensor_struct
->
lidar_altitude
=
-
raw_sensor_struct
->
lidar_distance_m
;
//
sensor_struct->lidar_altitude = -raw_sensor_struct->lidar_distance_m;
// Simply copy optical flow data
sensor_struct
->
optical_flow
=
raw_sensor_struct
->
optical_flow
;
...
...
@@ -123,6 +122,25 @@ int sensor_processing(log_t* log_struct, user_input_t *user_input_struct, raw_se
//sensor_struct->optical_flow.yVel = biquad_execute(&sensor_struct->flow_y_filt, -sensor_struct->optical_flow.yVel);
flow_to_vel
(
&
sensor_struct
->
optical_flow
,
raw_sensor_struct
->
lidar_distance_m
);
/*
* Altitude double complementary filter
*/
static
float
alt_alpha
=
0
.
9975
;
static
float
filtered_vel
=
0
;
static
float
filtered_alt
=
0
;
static
float
last_lidar
=
0
;
float
this_lidar
=
raw_sensor_struct
->
lidar_distance_m
;
// 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
())
+
(
1
-
alt_alpha
)
*
(
this_lidar
-
last_lidar
);
filtered_alt
=
alt_alpha
*
(
filtered_alt
+
filtered_vel
*
get_last_loop_time
())
+
(
1
-
alt_alpha
)
*
(
this_lidar
);
last_lidar
=
this_lidar
;
sensor_struct
->
lidar_altitude
=
filtered_alt
;
return
0
;
}
...
...
This diff is collapsed.
Click to expand it.
quad/xsdk_workspace/real_quad/src/hw_impl_zybo_imu.c
+
1
−
1
View file @
2bf20b5c
...
...
@@ -48,7 +48,7 @@
#define ACCEL_X_BIAS 0.023f
#define ACCEL_Y_BIAS 0.009f
#define ACCEL_Z_BIAS 0.0
87
f
#define ACCEL_Z_BIAS 0.0
686
f
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
);
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment