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
e6c6161e
Commit
e6c6161e
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
APM: fixed mission reset by setting waypoint to zero
this does a full mission reset (equivalent to rebooting)
parent
8c1766f5
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
ArduPlane/commands.pde
+1
-0
1 addition, 0 deletions
ArduPlane/commands.pde
ArduPlane/commands_process.pde
+9
-1
9 additions, 1 deletion
ArduPlane/commands_process.pde
ArduPlane/control_modes.pde
+1
-1
1 addition, 1 deletion
ArduPlane/control_modes.pde
with
11 additions
and
2 deletions
ArduPlane/commands.pde
+
1
−
0
View file @
e6c6161e
...
...
@@ -9,6 +9,7 @@ static void init_commands()
nav_command_ID
=
NO_COMMAND
;
non_nav_command_ID
=
NO_COMMAND
;
next_nav_command
.
id
=
CMD_BLANK
;
nav_command_index
=
0
;
}
static
void
update_auto
()
...
...
This diff is collapsed.
Click to expand it.
ArduPlane/commands_process.pde
+
9
−
1
View file @
e6c6161e
...
...
@@ -4,7 +4,15 @@
//----------------------------------------
void
change_command
(
uint8_t
cmd_index
)
{
struct
Location
temp
=
get_cmd_with_index
(
cmd_index
);
struct
Location
temp
;
if
(
cmd_index
==
0
)
{
init_commands
();
gcs_send_text_fmt
(
PSTR
(
"Received Request - reset mission"
));
return
;
}
temp
=
get_cmd_with_index
(
cmd_index
);
if
(
temp
.
id
>
MAV_CMD_NAV_LAST
)
{
gcs_send_text_P
(
SEVERITY_LOW
,
PSTR
(
"Bad Request - cannot change to non-Nav cmd"
));
...
...
This diff is collapsed.
Click to expand it.
ArduPlane/control_modes.pde
+
1
−
1
View file @
e6c6161e
...
...
@@ -39,7 +39,7 @@ static void read_control_switch()
APM_RC
.
InputCh
(
g
.
reset_mission_chan
-
1
)
>
RESET_SWITCH_CHAN_PWM
)
{
// reset to first waypoint in mission
prev_WP
=
current_loc
;
change_command
(
1
);
change_command
(
0
);
}
switch_debouncer
=
false
;
...
...
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