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
655446fe
Commit
655446fe
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
INS: make it possible to do accel cal on a different serial port
parent
8aa8f81b
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
libraries/AP_InertialSensor/AP_InertialSensor.cpp
+9
-28
9 additions, 28 deletions
libraries/AP_InertialSensor/AP_InertialSensor.cpp
libraries/AP_InertialSensor/AP_InertialSensor.h
+3
-2
3 additions, 2 deletions
libraries/AP_InertialSensor/AP_InertialSensor.h
with
12 additions
and
30 deletions
libraries/AP_InertialSensor/AP_InertialSensor.cpp
+
9
−
28
View file @
655446fe
...
@@ -233,7 +233,9 @@ AP_InertialSensor::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_l
...
@@ -233,7 +233,9 @@ AP_InertialSensor::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_l
#if !defined( __AVR_ATmega1280__ )
#if !defined( __AVR_ATmega1280__ )
// perform accelerometer calibration including providing user instructions and feedback
// perform accelerometer calibration including providing user instructions and feedback
bool
AP_InertialSensor
::
calibrate_accel
(
void
(
*
delay_cb
)(
unsigned
long
t
),
void
(
*
flash_leds_cb
)(
bool
on
),
void
(
*
send_msg
)(
const
prog_char_t
*
,
...))
bool
AP_InertialSensor
::
calibrate_accel
(
void
(
*
delay_cb
)(
unsigned
long
t
),
void
(
*
flash_leds_cb
)(
bool
on
),
void
(
*
send_msg
)(
const
prog_char_t
*
,
...),
void
(
*
wait_key
)(
void
))
{
{
Vector3f
samples
[
6
];
Vector3f
samples
[
6
];
Vector3f
new_offsets
;
Vector3f
new_offsets
;
...
@@ -274,20 +276,9 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
...
@@ -274,20 +276,9 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
msg
=
PSTR
(
"on it's back"
);
msg
=
PSTR
(
"on it's back"
);
break
;
break
;
}
}
if
(
send_msg
==
NULL
)
{
send_msg
(
PSTR
(
"USER: Place APM %S and press any key.
\n
"
),
msg
);
Serial
.
printf_P
(
PSTR
(
"USER: Place APM %S and press any key.
\n
"
),
msg
);
}
else
{
send_msg
(
PSTR
(
"USER: Place APM %S and press any key.
\n
"
),
msg
);
}
// wait for user input
wait_key
();
while
(
!
Serial
.
available
()
)
{
delay_cb
(
20
);
}
// clear unput buffer
while
(
Serial
.
available
()
)
{
Serial
.
read
();
}
// clear out any existing samples from ins
// clear out any existing samples from ins
update
();
update
();
...
@@ -306,11 +297,7 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
...
@@ -306,11 +297,7 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
// run the calibration routine
// run the calibration routine
if
(
_calibrate_accel
(
samples
,
new_offsets
,
new_scaling
)
)
{
if
(
_calibrate_accel
(
samples
,
new_offsets
,
new_scaling
)
)
{
if
(
send_msg
==
NULL
)
{
send_msg
(
PSTR
(
"Calibration successful
\n
"
));
Serial
.
printf_P
(
PSTR
(
"Calibration successful
\n
"
));
}
else
{
send_msg
(
PSTR
(
"Calibration successful
\n
"
));
}
// set and save calibration
// set and save calibration
_accel_offset
.
set
(
new_offsets
);
_accel_offset
.
set
(
new_offsets
);
...
@@ -319,15 +306,9 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
...
@@ -319,15 +306,9 @@ bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
return
true
;
return
true
;
}
}
if
(
send_msg
==
NULL
)
{
send_msg
(
PSTR
(
"Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)
\n
"
),
Serial
.
printf_P
(
PSTR
(
"Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)
\n
"
),
new_offsets
.
x
,
new_offsets
.
y
,
new_offsets
.
z
,
new_offsets
.
x
,
new_offsets
.
y
,
new_offsets
.
z
,
new_scaling
.
x
,
new_scaling
.
y
,
new_scaling
.
z
);
new_scaling
.
x
,
new_scaling
.
y
,
new_scaling
.
z
);
}
else
{
send_msg
(
PSTR
(
"Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)
\n
"
),
new_offsets
.
x
,
new_offsets
.
y
,
new_offsets
.
z
,
new_scaling
.
x
,
new_scaling
.
y
,
new_scaling
.
z
);
}
// restore original scaling and offsets
// restore original scaling and offsets
_accel_offset
.
set
(
orig_offset
);
_accel_offset
.
set
(
orig_offset
);
_accel_scale
.
set
(
orig_scale
);
_accel_scale
.
set
(
orig_scale
);
...
...
This diff is collapsed.
Click to expand it.
libraries/AP_InertialSensor/AP_InertialSensor.h
+
3
−
2
View file @
655446fe
...
@@ -52,8 +52,9 @@ public:
...
@@ -52,8 +52,9 @@ public:
#if !defined( __AVR_ATmega1280__ )
#if !defined( __AVR_ATmega1280__ )
// perform accelerometer calibration including providing user instructions and feedback
// perform accelerometer calibration including providing user instructions and feedback
virtual
bool
calibrate_accel
(
void
(
*
delay_cb
)(
unsigned
long
t
),
virtual
bool
calibrate_accel
(
void
(
*
delay_cb
)(
unsigned
long
t
),
void
(
*
flash_leds_cb
)(
bool
on
)
=
NULL
,
void
(
*
flash_leds_cb
)(
bool
on
),
void
(
*
send_msg
)(
const
prog_char_t
*
,
...)
=
NULL
);
void
(
*
send_msg
)(
const
prog_char_t
*
,
...),
void
(
*
wait_key
)(
void
));
#endif
#endif
/// Perform cold-start initialisation for just the gyros.
/// Perform cold-start initialisation for just the gyros.
...
...
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