Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
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
Ardupilot
Commits
219fed14
Commit
219fed14
authored
13 years ago
by
Jason Short
Browse files
Options
Downloads
Patches
Plain Diff
Arducopter: deprecated the get_nav_yaw_offset function.
Small Toy mode updates
parent
8f7eba4f
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduCopter/Attitude.pde
+9
-6
9 additions, 6 deletions
ArduCopter/Attitude.pde
with
9 additions
and
6 deletions
ArduCopter/Attitude.pde
+
9
−
6
View file @
219fed14
...
...
@@ -479,8 +479,10 @@ static void reset_stability_I(void)
throttle control
****************************************************************/
/* Depricated
static long
get_nav_yaw_offset
(
int
yaw_input
,
int
reset
)
//
get_nav_yaw_offset(int yaw_input, int reset)
{
int32_t _yaw;
...
...
@@ -501,6 +503,7 @@ get_nav_yaw_offset(int yaw_input, int reset)
}
}
}
*/
static
int16_t
get_angle_boost
(
int16_t
value
)
{
...
...
@@ -784,22 +787,22 @@ void roll_pitch_toy()
// user from Loiter mode
int16_t
yaw_rate
=
g
.
rc_1
.
control_in
/
g
.
toy_yaw_rate
;
//nav_yaw += yaw_rate / 100;
//nav_yaw = wrap_360(nav_yaw);
//g.rc_4.servo_out = get_stabilize_yaw(nav_yaw);
if
(
g
.
rc_1
.
control_in
!=
0
){
// roll
g
.
rc_4
.
servo_out
=
get_acro_yaw
(
yaw_rate
/
2
);
yaw_stopped
=
false
;
yaw_timer
=
150
;
}
else
if
(
!
yaw_stopped
){
g
.
rc_4
.
servo_out
=
get_acro_yaw
(
0
);
yaw_timer
--
;
if
(
yaw_timer
==
0
){
if
((
yaw_timer
==
0
)
||
(
fabs
(
omega
.
z
)
<
.17
)){
yaw_stopped
=
true
;
nav_yaw
=
ahrs
.
yaw_sensor
;
}
}
else
{
if
(
motors
.
armed
()
==
false
)
nav_yaw
=
ahrs
.
yaw_sensor
;
g
.
rc_4
.
servo_out
=
get_stabilize_yaw
(
nav_yaw
);
}
...
...
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