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
bfb2c1ee
Commit
bfb2c1ee
authored
13 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
GPS: open the GPS serial port with a 256 byte buffer
the UBLOX needs more than 128 bytes for reliable parsing
parent
ddebf7b4
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
ArduCopter/system.pde
+3
-1
3 additions, 1 deletion
ArduCopter/system.pde
ArduPlane/system.pde
+1
-1
1 addition, 1 deletion
ArduPlane/system.pde
with
4 additions
and
2 deletions
ArduCopter/system.pde
+
3
−
1
View file @
bfb2c1ee
...
@@ -83,7 +83,9 @@ static void init_ardupilot()
...
@@ -83,7 +83,9 @@ static void init_ardupilot()
// GPS serial port.
// GPS serial port.
//
//
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU
Serial1
.
begin
(
38400
,
128
,
16
);
// standard gps running. Note that we need a 256 byte buffer for some
// GPS types (eg. UBLOX)
Serial1
.
begin
(
38400
,
256
,
16
);
#endif
#endif
Serial
.
printf_P
(
PSTR
(
"
\n\n
Init "
THISFIRMWARE
Serial
.
printf_P
(
PSTR
(
"
\n\n
Init "
THISFIRMWARE
...
...
This diff is collapsed.
Click to expand it.
ArduPlane/system.pde
+
1
−
1
View file @
bfb2c1ee
...
@@ -86,7 +86,7 @@ static void init_ardupilot()
...
@@ -86,7 +86,7 @@ static void init_ardupilot()
// GPS serial port.
// GPS serial port.
//
//
// standard gps running
// standard gps running
Serial1
.
begin
(
38400
,
128
,
16
);
Serial1
.
begin
(
38400
,
256
,
16
);
Serial
.
printf_P
(
PSTR
(
"
\n\n
Init "
THISFIRMWARE
Serial
.
printf_P
(
PSTR
(
"
\n\n
Init "
THISFIRMWARE
"
\n\n
Free RAM: %u
\n
"
),
"
\n\n
Free RAM: %u
\n
"
),
...
...
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