Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
B
Baitboat
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD 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
OpenSource
Baitboat
Commits
05fedbf9
Commit
05fedbf9
authored
10 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Copter: minor formatting fixes
parent
91bff632
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
ArduCopter/control_auto.pde
+2
-2
2 additions, 2 deletions
ArduCopter/control_auto.pde
ArduCopter/control_land.pde
+4
-2
4 additions, 2 deletions
ArduCopter/control_land.pde
ArduCopter/control_rtl.pde
+1
-0
1 addition, 0 deletions
ArduCopter/control_rtl.pde
with
7 additions
and
4 deletions
ArduCopter/control_auto.pde
+
2
−
2
View file @
05fedbf9
...
...
@@ -323,12 +323,12 @@ static void auto_land_run()
// run loiter controller
wp_nav
.
update_loiter
(
ekfGndSpdLimit
,
ekfNavVelGainScaler
);
float
cmb_rate
=
get_land_descent_speed
();
// call z-axis position controller
float
cmb_rate
=
get_land_descent_speed
();
pos_control
.
set_alt_target_from_climb_rate
(
cmb_rate
,
G_Dt
,
true
);
pos_control
.
update_z_controller
();
// record desired climb rate for logging
desired_climb_rate
=
cmb_rate
;
// roll & pitch from waypoint controller, yaw rate from pilot
...
...
This diff is collapsed.
Click to expand it.
ArduCopter/control_land.pde
+
4
−
2
View file @
05fedbf9
...
...
@@ -102,7 +102,7 @@ static void land_gps_run()
// call attitude controller
attitude_control
.
angle_ef_roll_pitch_rate_ef_yaw
(
wp_nav
.
get_roll
(),
wp_nav
.
get_pitch
(),
target_yaw_rate
);
//pause 4 seconds before beginning land descent
//
pause 4 seconds before beginning land descent
float
cmb_rate
;
if
(
land_pause
&&
millis
()
-
land_start_time
<
4000
)
{
cmb_rate
=
0
;
...
...
@@ -111,6 +111,7 @@ static void land_gps_run()
cmb_rate
=
get_land_descent_speed
();
}
// record desired climb rate for logging
desired_climb_rate
=
cmb_rate
;
// update altitude target and call position controller
...
...
@@ -162,7 +163,7 @@ static void land_nogps_run()
// call attitude controller
attitude_control
.
angle_ef_roll_pitch_rate_ef_yaw_smooth
(
target_roll
,
target_pitch
,
target_yaw_rate
,
get_smoothing_gain
());
//pause 4 seconds before beginning land descent
//
pause 4 seconds before beginning land descent
float
cmb_rate
;
if
(
land_pause
&&
millis
()
-
land_start_time
<
LAND_WITH_DELAY_MS
)
{
cmb_rate
=
0
;
...
...
@@ -171,6 +172,7 @@ static void land_nogps_run()
cmb_rate
=
get_land_descent_speed
();
}
// record desired climb rate for logging
desired_climb_rate
=
cmb_rate
;
// call position controller
...
...
This diff is collapsed.
Click to expand it.
ArduCopter/control_rtl.pde
+
1
−
0
View file @
05fedbf9
...
...
@@ -380,6 +380,7 @@ static void rtl_land_run()
pos_control
.
set_alt_target_from_climb_rate
(
cmb_rate
,
G_Dt
,
true
);
pos_control
.
update_z_controller
();
// record desired climb rate for logging
desired_climb_rate
=
cmb_rate
;
// roll & pitch from waypoint controller, yaw rate from pilot
...
...
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