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
b1342c2d
Commit
b1342c2d
authored
10 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
GCS_MAVLink: send SCALED_PRESSURE2 if available
parent
19c717df
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
libraries/GCS_MAVLink/GCS_Common.cpp
+16
-4
16 additions, 4 deletions
libraries/GCS_MAVLink/GCS_Common.cpp
with
16 additions
and
4 deletions
libraries/GCS_MAVLink/GCS_Common.cpp
+
16
−
4
View file @
b1342c2d
...
@@ -1044,13 +1044,25 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
...
@@ -1044,13 +1044,25 @@ void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &comp
void
GCS_MAVLINK
::
send_scaled_pressure
(
AP_Baro
&
barometer
)
void
GCS_MAVLINK
::
send_scaled_pressure
(
AP_Baro
&
barometer
)
{
{
float
pressure
=
barometer
.
get_pressure
();
uint32_t
now
=
hal
.
scheduler
->
millis
();
float
pressure
=
barometer
.
get_pressure
(
0
);
mavlink_msg_scaled_pressure_send
(
mavlink_msg_scaled_pressure_send
(
chan
,
chan
,
hal
.
scheduler
->
millis
()
,
now
,
pressure
*
0.01
f
,
// hectopascal
pressure
*
0.01
f
,
// hectopascal
(
pressure
-
barometer
.
get_ground_pressure
())
*
0.01
f
,
// hectopascal
(
pressure
-
barometer
.
get_ground_pressure
(
0
))
*
0.01
f
,
// hectopascal
barometer
.
get_temperature
()
*
100
);
// 0.01 degrees C
barometer
.
get_temperature
(
0
)
*
100
);
// 0.01 degrees C
#if BARO_MAX_INSTANCES > 1
if
(
barometer
.
num_instances
()
>
1
)
{
pressure
=
barometer
.
get_pressure
(
1
);
mavlink_msg_scaled_pressure2_send
(
chan
,
now
,
pressure
*
0.01
f
,
// hectopascal
(
pressure
-
barometer
.
get_ground_pressure
(
1
))
*
0.01
f
,
// hectopascal
barometer
.
get_temperature
(
1
)
*
100
);
// 0.01 degrees C
}
#endif
}
}
void
GCS_MAVLINK
::
send_sensor_offsets
(
const
AP_InertialSensor
&
ins
,
const
Compass
&
compass
,
AP_Baro
&
barometer
)
void
GCS_MAVLINK
::
send_sensor_offsets
(
const
AP_InertialSensor
&
ins
,
const
Compass
&
compass
,
AP_Baro
&
barometer
)
...
...
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