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
a2aa4e1e
Commit
a2aa4e1e
authored
13 years ago
by
Jason Short
Browse files
Options
Downloads
Patches
Plain Diff
renamed set_cmd function
parent
a0cc3bf8
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/commands.pde
+4
-4
4 additions, 4 deletions
ArduCopter/commands.pde
with
4 additions
and
4 deletions
ArduCopter/commands.pde
+
4
−
4
View file @
a2aa4e1e
...
...
@@ -50,11 +50,11 @@ static struct Location get_cmd_with_index(int i)
}
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
//if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options &
WP
_OPTION
_ALT
_RELATIVE){
//if((temp.id < MAV_CMD_NAV_LAST || temp.id == MAV_CMD_CONDITION_CHANGE_ALT) && temp.options &
MASK
_OPTION
S
_RELATIVE
_ALT
){
//temp.alt += home.alt;
//}
if
(
temp
.
options
&
WP
_OPTION_RELATIVE
){
if
(
temp
.
options
&
MASK
_OPTION
S
_RELATIVE
_ALT
){
// If were relative, just offset from home
temp
.
lat
+=
home
.
lat
;
temp
.
lng
+=
home
.
lng
;
...
...
@@ -65,7 +65,7 @@ static struct Location get_cmd_with_index(int i)
// Setters
// -------
static
void
set_c
omman
d_with_index
(
struct
Location
temp
,
int
i
)
static
void
set_c
m
d_with_index
(
struct
Location
temp
,
int
i
)
{
i
=
constrain
(
i
,
0
,
g
.
command_total
.
get
());
//Serial.printf("set_command: %d with id: %d\n", i, temp.id);
...
...
@@ -203,7 +203,7 @@ static void init_home()
// Save Home to EEPROM
// -------------------
// no need to save this to EPROM
set_c
omman
d_with_index
(
home
,
0
);
set_c
m
d_with_index
(
home
,
0
);
print_wp
(
&
home
,
0
);
// Save prev loc this makes the calcs look better before commands are loaded
...
...
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