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
cf1f05a1
Commit
cf1f05a1
authored
11 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
AP_Airspeed: expose get_temperature()
parent
fc3ed61e
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_Airspeed/AP_Airspeed.cpp
+14
-2
14 additions, 2 deletions
libraries/AP_Airspeed/AP_Airspeed.cpp
libraries/AP_Airspeed/AP_Airspeed.h
+6
-0
6 additions, 0 deletions
libraries/AP_Airspeed/AP_Airspeed.h
with
20 additions
and
2 deletions
libraries/AP_Airspeed/AP_Airspeed.cpp
+
14
−
2
View file @
cf1f05a1
...
...
@@ -49,7 +49,7 @@ extern const AP_HAL::HAL& hal;
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
#define ARSPD_DEFAULT_PIN 16
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#define ARSPD_DEFAULT_PIN
65
#define ARSPD_DEFAULT_PIN
AP_AIRSPEED_I2C_PIN
#else
#define ARSPD_DEFAULT_PIN 0
#endif
...
...
@@ -122,7 +122,7 @@ float AP_Airspeed::get_pressure(void)
return
0
;
}
float
pressure
=
0
;
if
(
_pin
==
65
)
{
if
(
_pin
==
AP_AIRSPEED_I2C_PIN
)
{
_healthy
=
digital
.
get_differential_pressure
(
pressure
);
}
else
{
_healthy
=
analog
.
get_differential_pressure
(
pressure
);
...
...
@@ -130,6 +130,18 @@ float AP_Airspeed::get_pressure(void)
return
pressure
;
}
// get a temperature reading if possible
bool
AP_Airspeed
::
get_temperature
(
float
&
temperature
)
{
if
(
!
_enable
)
{
return
false
;
}
if
(
_pin
==
AP_AIRSPEED_I2C_PIN
)
{
return
digital
.
get_temperature
(
temperature
);
}
return
false
;
}
// calibrate the airspeed. This must be called at least once before
// the get_airspeed() interface can be used
void
AP_Airspeed
::
calibrate
()
...
...
This diff is collapsed.
Click to expand it.
libraries/AP_Airspeed/AP_Airspeed.h
+
6
−
0
View file @
cf1f05a1
...
...
@@ -78,6 +78,9 @@ public:
return
_ratio
;
}
// get temperature if available
bool
get_temperature
(
float
&
temperature
);
// set the airspeed ratio (dimensionless)
void
set_airspeed_ratio
(
float
ratio
)
{
_ratio
.
set
(
ratio
);
...
...
@@ -158,5 +161,8 @@ private:
#endif
};
// the virtual pin for digital airspeed sensors
#define AP_AIRSPEED_I2C_PIN 65
#endif // __AP_AIRSPEED_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