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
154c55c9
Commit
154c55c9
authored
13 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
desktop: more fixes for DataFlash filesystem changes
parent
81a4c875
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/Desktop/support/DataFlash.cpp
+10
-10
10 additions, 10 deletions
libraries/Desktop/support/DataFlash.cpp
with
10 additions
and
10 deletions
libraries/Desktop/support/DataFlash.cpp
+
10
−
10
View file @
154c55c9
...
@@ -16,7 +16,7 @@
...
@@ -16,7 +16,7 @@
static
int
flash_fd
;
static
int
flash_fd
;
static
uint8_t
buffer
[
2
][
DF_PAGE_SIZE
];
static
uint8_t
buffer
[
2
][
DF_PAGE_SIZE
];
#define OVERWRITE_DATA
0
// 0: When reach the end page stop, 1: Start overwritten from page 1
#define OVERWRITE_DATA
1
// 0: When reach the end page stop, 1: Start overwritten from page 1
// Constructors ////////////////////////////////////////////////////////////////
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_Class
::
DataFlash_Class
()
DataFlash_Class
::
DataFlash_Class
()
...
@@ -120,7 +120,7 @@ void DataFlash_Class::ChipErase ()
...
@@ -120,7 +120,7 @@ void DataFlash_Class::ChipErase ()
void
DataFlash_Class
::
StartWrite
(
int16_t
PageAdr
)
void
DataFlash_Class
::
StartWrite
(
int16_t
PageAdr
)
{
{
df_BufferNum
=
1
;
df_BufferNum
=
1
;
df_BufferIdx
=
0
;
df_BufferIdx
=
4
;
df_PageAdr
=
PageAdr
;
df_PageAdr
=
PageAdr
;
df_Stop_Write
=
0
;
df_Stop_Write
=
0
;
...
@@ -137,12 +137,12 @@ void DataFlash_Class::FinishWrite(void)
...
@@ -137,12 +137,12 @@ void DataFlash_Class::FinishWrite(void)
df_PageAdr
++
;
df_PageAdr
++
;
if
(
OVERWRITE_DATA
==
1
)
if
(
OVERWRITE_DATA
==
1
)
{
{
if
(
df_PageAdr
>=
4096
)
// If we reach the end of the memory, start from the begining
if
(
df_PageAdr
>=
DF_LAST_PAGE
)
// If we reach the end of the memory, start from the begining
df_PageAdr
=
1
;
df_PageAdr
=
1
;
}
}
else
else
{
{
if
(
df_PageAdr
>=
4096
)
// If we reach the end of the memory, stop here
if
(
df_PageAdr
>=
DF_LAST_PAGE
)
// If we reach the end of the memory, stop here
df_Stop_Write
=
1
;
df_Stop_Write
=
1
;
}
}
...
@@ -167,17 +167,17 @@ void DataFlash_Class::WriteByte(byte data)
...
@@ -167,17 +167,17 @@ void DataFlash_Class::WriteByte(byte data)
df_BufferIdx
++
;
df_BufferIdx
++
;
if
(
df_BufferIdx
>=
df_PageSize
)
// End of buffer?
if
(
df_BufferIdx
>=
df_PageSize
)
// End of buffer?
{
{
df_BufferIdx
=
0
;
df_BufferIdx
=
4
;
BufferToPage
(
df_BufferNum
,
df_PageAdr
,
0
);
// Write Buffer to memory, NO WAIT
BufferToPage
(
df_BufferNum
,
df_PageAdr
,
0
);
// Write Buffer to memory, NO WAIT
df_PageAdr
++
;
df_PageAdr
++
;
if
(
OVERWRITE_DATA
==
1
)
if
(
OVERWRITE_DATA
==
1
)
{
{
if
(
df_PageAdr
>=
4096
)
// If we reach the end of the memory, start from the begining
if
(
df_PageAdr
>=
DF_LAST_PAGE
)
// If we reach the end of the memory, start from the begining
df_PageAdr
=
1
;
df_PageAdr
=
1
;
}
}
else
else
{
{
if
(
df_PageAdr
>=
4096
)
// If we reach the end of the memory, stop here
if
(
df_PageAdr
>=
DF_LAST_PAGE
)
// If we reach the end of the memory, stop here
df_Stop_Write
=
1
;
df_Stop_Write
=
1
;
}
}
...
@@ -218,7 +218,7 @@ int16_t DataFlash_Class::GetPage()
...
@@ -218,7 +218,7 @@ int16_t DataFlash_Class::GetPage()
void
DataFlash_Class
::
StartRead
(
int16_t
PageAdr
)
void
DataFlash_Class
::
StartRead
(
int16_t
PageAdr
)
{
{
df_Read_BufferNum
=
1
;
df_Read_BufferNum
=
1
;
df_Read_BufferIdx
=
0
;
df_Read_BufferIdx
=
4
;
df_Read_PageAdr
=
PageAdr
;
df_Read_PageAdr
=
PageAdr
;
WaitReady
();
WaitReady
();
PageToBuffer
(
df_Read_BufferNum
,
df_Read_PageAdr
);
// Write Memory page to buffer
PageToBuffer
(
df_Read_BufferNum
,
df_Read_PageAdr
);
// Write Memory page to buffer
...
@@ -234,10 +234,10 @@ byte DataFlash_Class::ReadByte()
...
@@ -234,10 +234,10 @@ byte DataFlash_Class::ReadByte()
df_Read_BufferIdx
++
;
df_Read_BufferIdx
++
;
if
(
df_Read_BufferIdx
>=
df_PageSize
)
// End of buffer?
if
(
df_Read_BufferIdx
>=
df_PageSize
)
// End of buffer?
{
{
df_Read_BufferIdx
=
0
;
df_Read_BufferIdx
=
4
;
PageToBuffer
(
df_Read_BufferNum
,
df_Read_PageAdr
);
// Write memory page to Buffer
PageToBuffer
(
df_Read_BufferNum
,
df_Read_PageAdr
);
// Write memory page to Buffer
df_Read_PageAdr
++
;
df_Read_PageAdr
++
;
if
(
df_Read_PageAdr
>=
4096
)
// If we reach the end of the memory, start from the begining
if
(
df_Read_PageAdr
>=
DF_LAST_PAGE
)
// If we reach the end of the memory, start from the begining
{
{
df_Read_PageAdr
=
0
;
df_Read_PageAdr
=
0
;
df_Read_END
=
true
;
df_Read_END
=
true
;
...
...
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