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
9f63de9b
Commit
9f63de9b
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
AC_PosControl: set_speed_z accepts positive descent speeds
parent
466e9db1
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
libraries/AC_AttitudeControl/AC_PosControl.cpp
+3
-0
3 additions, 0 deletions
libraries/AC_AttitudeControl/AC_PosControl.cpp
libraries/AC_AttitudeControl/AC_PosControl.h
+1
-2
1 addition, 2 deletions
libraries/AC_AttitudeControl/AC_PosControl.h
with
4 additions
and
2 deletions
libraries/AC_AttitudeControl/AC_PosControl.cpp
+
3
−
0
View file @
9f63de9b
...
...
@@ -77,6 +77,9 @@ AC_PosControl::AC_PosControl(const AP_AHRS& ahrs, const AP_InertialNav& inav,
/// speed_down should be a negative number
void
AC_PosControl
::
set_speed_z
(
float
speed_down
,
float
speed_up
)
{
// ensure speed_down is always negative
speed_down
=
-
fabs
(
speed_down
);
if
((
fabs
(
_speed_down_cms
-
speed_down
)
>
1.0
f
)
||
(
fabs
(
_speed_up_cms
-
speed_up
)
>
1.0
f
))
{
_speed_down_cms
=
speed_down
;
_speed_up_cms
=
speed_up
;
...
...
This diff is collapsed.
Click to expand it.
libraries/AC_AttitudeControl/AC_PosControl.h
+
1
−
2
View file @
9f63de9b
...
...
@@ -62,8 +62,7 @@ public:
void
set_alt_max
(
float
alt
)
{
_alt_max
=
alt
;
}
/// set_speed_z - sets maximum climb and descent rates
/// To-Do: call this in the main code as part of flight mode initialisation
/// speed_down should be a negative number
/// speed_down can be positive or negative but will always be interpreted as a descent speed
/// leash length will be recalculated the next time update_z_controller() is called
void
set_speed_z
(
float
speed_down
,
float
speed_up
);
...
...
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