mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Add TSYS01 'celsius' object
This commit is contained in:
parent
ca603e1517
commit
098a716d41
@ -448,6 +448,18 @@ void NOINLINE Sub::send_rpm(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Work around to get temperature sensor data out
|
||||||
|
void NOINLINE Sub::send_temperature(mavlink_channel_t chan) {
|
||||||
|
if(!celsius.healthy()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
mavlink_msg_scaled_pressure3_send(
|
||||||
|
chan,
|
||||||
|
AP_HAL::millis(),
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
celsius.temperature() * 100);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
send PID tuning message
|
send PID tuning message
|
||||||
@ -622,6 +634,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
case MSG_RAW_IMU2:
|
case MSG_RAW_IMU2:
|
||||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||||
send_scaled_pressure(sub.barometer);
|
send_scaled_pressure(sub.barometer);
|
||||||
|
sub.send_temperature(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RAW_IMU3:
|
case MSG_RAW_IMU3:
|
||||||
|
@ -88,6 +88,7 @@
|
|||||||
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
||||||
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
|
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
|
||||||
#include "../libraries/AP_LeakDetector/AP_LeakDetector.h" // Leak detector
|
#include "../libraries/AP_LeakDetector/AP_LeakDetector.h" // Leak detector
|
||||||
|
#include <AP_TemperatureSensor/TSYS01.h>
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
|
|
||||||
@ -176,6 +177,7 @@ private:
|
|||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes;
|
AP_Int8 *flight_modes;
|
||||||
|
|
||||||
|
TSYS01 celsius;
|
||||||
AP_Baro barometer;
|
AP_Baro barometer;
|
||||||
Compass compass;
|
Compass compass;
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
@ -538,6 +540,7 @@ private:
|
|||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
#endif
|
#endif
|
||||||
|
void send_temperature(mavlink_channel_t chan);
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
void send_pid_tuning(mavlink_channel_t chan);
|
||||||
void gcs_send_message(enum ap_message id);
|
void gcs_send_message(enum ap_message id);
|
||||||
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
void gcs_send_mission_item_reached_message(uint16_t mission_index);
|
||||||
|
@ -57,3 +57,4 @@ LIBRARIES += AP_JSButton
|
|||||||
LIBRARIES += AP_LeakDetector
|
LIBRARIES += AP_LeakDetector
|
||||||
LIBRARIES += AP_Gripper
|
LIBRARIES += AP_Gripper
|
||||||
LIBRARIES += AP_Beacon
|
LIBRARIES += AP_Beacon
|
||||||
|
LIBRARIES += AP_TemperatureSensor
|
||||||
|
@ -124,6 +124,8 @@ void Sub::init_ardupilot()
|
|||||||
|
|
||||||
barometer.init();
|
barometer.init();
|
||||||
|
|
||||||
|
celsius.init();
|
||||||
|
|
||||||
// Register the mavlink service callback. This will run
|
// Register the mavlink service callback. This will run
|
||||||
// anytime there are more than 5ms remaining in a call to
|
// anytime there are more than 5ms remaining in a call to
|
||||||
// hal.scheduler->delay.
|
// hal.scheduler->delay.
|
||||||
|
@ -30,6 +30,7 @@ def build(bld):
|
|||||||
'AP_Proximity',
|
'AP_Proximity',
|
||||||
'AP_Gripper',
|
'AP_Gripper',
|
||||||
'AP_Beacon',
|
'AP_Beacon',
|
||||||
|
'AP_TemperatureSensor'
|
||||||
],
|
],
|
||||||
use='mavlink',
|
use='mavlink',
|
||||||
)
|
)
|
||||||
|
Loading…
Reference in New Issue
Block a user