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
eb1b2c42
Commit
eb1b2c42
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
OptFlow: correct SPI mode and baud rates
parent
d6549319
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
libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp
+5
-3
5 additions, 3 deletions
libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp
with
5 additions
and
3 deletions
libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp
+
5
−
3
View file @
eb1b2c42
...
...
@@ -42,7 +42,7 @@ void APM2SPIDeviceManager::init(void* machtnichts) {
AVRDigitalSource
*
optflow_cs
=
new
AVRDigitalSource
(
_BV
(
3
),
PF
);
/* optflow: divide clock by 8 to 2Mhz
* spcr gets bit SPR0, spsr gets bit SPI2X */
_optflow_spi0
=
new
AVRSPI0DeviceDriver
(
optflow_cs
,
_BV
(
SPR0
)
,
_BV
(
SPR0
),
_BV
(
SPI2X
));
_optflow_spi0
=
new
AVRSPI0DeviceDriver
(
optflow_cs
,
_BV
(
SPR0
)
|
_BV
(
CPOL
)
|
_BV
(
CPHA
),
_BV
(
SPR0
)
|
_BV
(
CPOL
)
|
_BV
(
CPHA
),
_BV
(
SPI2X
));
_optflow_spi0
->
init
();
/* Dataflash CS is on Arduino pin 28, PORTA6 */
...
...
@@ -53,8 +53,10 @@ void APM2SPIDeviceManager::init(void* machtnichts) {
_dataflash
=
new
AVRSPI3DeviceDriver
(
df_cs
,
0
,
0
);
_dataflash
->
init
();
/* XXX need correct mode and baud */
_optflow_spi3
=
new
AVRSPI3DeviceDriver
(
optflow_cs
,
0
,
0
);
/* optflow uses mode 3 and a clock of 2mhz
* ucsr3c = _BV(UCPHA3N)|_BV(UCPOL3) = 3
* ubrr3 = 3 */
_optflow_spi3
=
new
AVRSPI3DeviceDriver
(
optflow_cs
,
3
,
3
);
_optflow_spi3
->
init
();
}
...
...
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