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
6a2a0e92
Commit
6a2a0e92
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
Rover: use slewrate code from ArduPlane
parent
4254e880
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
APMrover2/Attitude.pde
+18
-13
18 additions, 13 deletions
APMrover2/Attitude.pde
with
18 additions
and
13 deletions
APMrover2/Attitude.pde
+
18
−
13
View file @
6a2a0e92
...
@@ -14,6 +14,20 @@ static void learning()
...
@@ -14,6 +14,20 @@ static void learning()
g
.
channel_rudder
.
servo_out
=
g
.
channel_roll
.
servo_out
;
g
.
channel_rudder
.
servo_out
=
g
.
channel_roll
.
servo_out
;
}
}
/*****************************************
* Throttle slew limit
*****************************************/
static
void
throttle_slew_limit
()
{
static
int16_t
last
=
1000
;
// if slew limit rate is set to zero then do not slew limit
if
(
g
.
throttle_slewrate
)
{
// limit throttle change by the given percentage per second
float
temp
=
g
.
throttle_slewrate
*
G_Dt
*
0.01
*
fabs
(
g
.
channel_throttle
.
radio_max
-
g
.
channel_throttle
.
radio_min
);
g
.
channel_throttle
.
radio_out
=
constrain
(
g
.
channel_throttle
.
radio_out
,
last
-
(
int
)
temp
,
last
+
(
int
)
temp
);
last
=
g
.
channel_throttle
.
radio_out
;
}
}
static
void
calc_throttle
()
static
void
calc_throttle
()
{
int
rov_speed
;
{
int
rov_speed
;
...
@@ -27,19 +41,7 @@ static void calc_throttle()
...
@@ -27,19 +41,7 @@ static void calc_throttle()
groundspeed_error
=
rov_speed
-
(
float
)
ground_speed
;
groundspeed_error
=
rov_speed
-
(
float
)
ground_speed
;
int
throttle_req
=
(
throttle_target
+
g
.
pidTeThrottle
.
get_pid
(
groundspeed_error
))
*
10
;
throttle
=
(
throttle_target
+
g
.
pidTeThrottle
.
get_pid
(
groundspeed_error
))
*
10
;
if
(
g
.
throttle_slewrate
>
0
)
{
if
(
throttle_req
>
throttle_last
)
throttle
=
throttle
+
g
.
throttle_slewrate
;
else
if
(
throttle_req
<
throttle_last
)
{
throttle
=
throttle
-
g
.
throttle_slewrate
;
}
throttle
=
constrain
(
throttle
,
500
,
throttle_req
);
throttle_last
=
throttle
;
}
else
{
throttle
=
throttle_req
;
}
g
.
channel_throttle
.
servo_out
=
constrain
(((
float
)
throttle
/
10.0
f
),
0
,
g
.
throttle_max
.
get
());
g
.
channel_throttle
.
servo_out
=
constrain
(((
float
)
throttle
/
10.0
f
),
0
,
g
.
throttle_max
.
get
());
}
}
...
@@ -105,6 +107,9 @@ static void set_servos(void)
...
@@ -105,6 +107,9 @@ static void set_servos(void)
}
}
if
(
control_mode
>=
AUTO
)
{
if
(
control_mode
>=
AUTO
)
{
// limit throttle movement speed
throttle_slew_limit
();
// convert 0 to 100% into PWM
// convert 0 to 100% into PWM
g
.
channel_throttle
.
calc_pwm
();
g
.
channel_throttle
.
calc_pwm
();
}
}
...
...
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