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
f541b2a0
Commit
f541b2a0
authored
12 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
AP_AnalogSource: added set_pin() interface
this allows pin numbers to be changed at runtime
parent
dac569a3
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_AnalogSource/AP_AnalogSource_Arduino.cpp
+29
-10
29 additions, 10 deletions
libraries/AP_AnalogSource/AP_AnalogSource_Arduino.cpp
libraries/AP_AnalogSource/AP_AnalogSource_Arduino.h
+7
-2
7 additions, 2 deletions
libraries/AP_AnalogSource/AP_AnalogSource_Arduino.h
with
36 additions
and
12 deletions
libraries/AP_AnalogSource/AP_AnalogSource_Arduino.cpp
+
29
−
10
View file @
f541b2a0
...
@@ -131,17 +131,9 @@ float AP_AnalogSource_Arduino::read(void)
...
@@ -131,17 +131,9 @@ float AP_AnalogSource_Arduino::read(void)
}
}
//
assign a slot in the pins_watched
//
remap pin numbers to physical pin
void
AP_AnalogSource_Arduino
::
assign_pin_index
(
uint8_t
pin
)
uint8_t
AP_AnalogSource_Arduino
::
_remap_pin
(
uint8_t
pin
)
{
{
// ensure we don't try to read from too many analog pins
if
(
num_pins_watched
==
MAX_PIN_SOURCES
)
{
while
(
true
)
{
Serial
.
printf_P
(
PSTR
(
"MAX_PIN_SOURCES REACHED
\n
"
));
delay
(
1000
);
}
}
if
(
pin
!=
ANALOG_PIN_VCC
)
{
if
(
pin
!=
ANALOG_PIN_VCC
)
{
// allow pin to be a channel (i.e. "A0") or an actual pin
// allow pin to be a channel (i.e. "A0") or an actual pin
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
...
@@ -154,7 +146,21 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
...
@@ -154,7 +146,21 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
if
(
pin
>=
14
)
pin
-=
14
;
if
(
pin
>=
14
)
pin
-=
14
;
#endif
#endif
}
}
return
pin
;
}
// assign a slot in the pins_watched
void
AP_AnalogSource_Arduino
::
_assign_pin_index
(
uint8_t
pin
)
{
// ensure we don't try to read from too many analog pins
if
(
num_pins_watched
==
MAX_PIN_SOURCES
)
{
while
(
true
)
{
Serial
.
printf_P
(
PSTR
(
"MAX_PIN_SOURCES REACHED
\n
"
));
delay
(
1000
);
}
}
pin
=
_remap_pin
(
pin
);
_pin_index
=
num_pins_watched
;
_pin_index
=
num_pins_watched
;
pins
[
_pin_index
].
pin
=
pin
;
pins
[
_pin_index
].
pin
=
pin
;
num_pins_watched
++
;
num_pins_watched
++
;
...
@@ -164,3 +170,16 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
...
@@ -164,3 +170,16 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
ADCSRA
|=
_BV
(
ADEN
);
ADCSRA
|=
_BV
(
ADEN
);
}
}
}
}
// change which pin to read
void
AP_AnalogSource_Arduino
::
set_pin
(
uint8_t
pin
)
{
pin
=
_remap_pin
(
pin
);
if
(
pins
[
_pin_index
].
pin
!=
pin
)
{
cli
();
pins
[
_pin_index
].
pin
=
pin
;
pins
[
_pin_index
].
sum
=
0
;
pins
[
_pin_index
].
sum_count
=
0
;
sei
();
}
}
This diff is collapsed.
Click to expand it.
libraries/AP_AnalogSource/AP_AnalogSource_Arduino.h
+
7
−
2
View file @
f541b2a0
...
@@ -15,7 +15,7 @@ class AP_AnalogSource_Arduino : public AP_AnalogSource
...
@@ -15,7 +15,7 @@ class AP_AnalogSource_Arduino : public AP_AnalogSource
public:
public:
AP_AnalogSource_Arduino
(
uint8_t
pin
,
float
prescale
=
1.0
)
:
AP_AnalogSource_Arduino
(
uint8_t
pin
,
float
prescale
=
1.0
)
:
_prescale
(
prescale
)
{
_prescale
(
prescale
)
{
assign_pin_index
(
pin
);
_
assign_pin_index
(
pin
);
}
}
// setup the timer callback
// setup the timer callback
...
@@ -34,11 +34,16 @@ public:
...
@@ -34,11 +34,16 @@ public:
// we last called read_average().
// we last called read_average().
float
read_average
(
void
);
float
read_average
(
void
);
// set the pin to be used for this source. This allows for the pin
// to be changed at runtime
void
set_pin
(
uint8_t
pin
);
private
:
private
:
uint8_t
_pin_index
;
uint8_t
_pin_index
;
float
_prescale
;
float
_prescale
;
void
assign_pin_index
(
uint8_t
pin
);
uint8_t
_remap_pin
(
uint8_t
pin
);
void
_assign_pin_index
(
uint8_t
pin
);
};
};
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__
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