Plane: added RPM logging

useful for seeing if a petrol motor is still running
This commit is contained in:
Andrew Tridgell 2015-09-24 20:58:18 +10:00
parent cdd4570f02
commit 458e967d06
8 changed files with 42 additions and 3 deletions

View File

@ -70,6 +70,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] PROGMEM = {
SCHED_TASK(one_second_loop, 50, 1000),
SCHED_TASK(check_long_failsafe, 15, 1000),
SCHED_TASK(read_receiver_rssi, 5, 1000),
SCHED_TASK(rpm_update, 5, 200),
SCHED_TASK(airspeed_ratio_update, 50, 1000),
SCHED_TASK(update_mount, 1, 1500),
SCHED_TASK(log_perf_info, 500, 1000),

View File

@ -470,6 +470,19 @@ void Plane::send_wind(mavlink_channel_t chan)
wind.z);
}
/*
send RPM packet
*/
void NOINLINE Plane::send_rpm(mavlink_channel_t chan)
{
if (rpm_sensor.healthy(0) || rpm_sensor.healthy(1)) {
mavlink_msg_rpm_send(
chan,
rpm_sensor.get_rpm(0),
rpm_sensor.get_rpm(1));
}
}
/*
send PID tuning message
*/
@ -799,7 +812,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break;
case MSG_RPM:
// unused
CHECK_PAYLOAD_SIZE(RPM);
plane.send_rpm(chan);
break;
case MSG_MISSION_ITEM_REACHED:
@ -1025,6 +1039,7 @@ GCS_MAVLINK::data_stream_send(void)
if (stream_trigger(STREAM_EXTRA1)) {
send_message(MSG_ATTITUDE);
send_message(MSG_SIMSTATE);
send_message(MSG_RPM);
if (plane.control_mode != MANUAL) {
send_message(MSG_PID_TUNING);
}

View File

@ -1193,6 +1193,10 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2),
#endif
// @Group: RPM
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp

View File

@ -141,9 +141,8 @@ public:
k_param_gcs_pid_mask,
k_param_crash_detection_enable,
k_param_land_abort_throttle_enable,
// 97: RSSI
k_param_rssi = 97,
k_param_rpm_sensor,
// 100: Arming parameters
k_param_arming = 100,

View File

@ -58,6 +58,7 @@
#include <AP_Camera/AP_Camera.h> // Photo or video camera
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RPM/AP_RPM.h>
#include <APM_OBC/APM_OBC.h>
#include <APM_Control/APM_Control.h>
@ -206,6 +207,8 @@ private:
} rangefinder_state;
#endif
AP_RPM rpm_sensor;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
NavEKF EKF{&ahrs, barometer, rangefinder};
@ -704,6 +707,7 @@ private:
void send_hwstatus(mavlink_channel_t chan);
void send_wind(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void send_rpm(mavlink_channel_t chan);
void send_rangefinder(mavlink_channel_t chan);
void send_current_waypoint(mavlink_channel_t chan);
void send_statustext(mavlink_channel_t chan);
@ -846,6 +850,7 @@ private:
void zero_airspeed(bool in_startup);
void read_battery(void);
void read_receiver_rssi(void);
void rpm_update(void);
void report_radio();
void report_ins();
void report_compass();

View File

@ -56,3 +56,4 @@ LIBRARIES += AP_HAL_FLYMAPLE
LIBRARIES += AP_HAL_Linux
LIBRARIES += AP_HAL_Empty
LIBRARIES += AP_HAL_VRBRAIN
LIBRARIES += AP_RPM

View File

@ -99,3 +99,15 @@ void Plane::read_receiver_rssi(void)
receiver_rssi = rssi.read_receiver_rssi_uint8();
}
/*
update RPM sensors
*/
void Plane::rpm_update(void)
{
rpm_sensor.update();
if (rpm_sensor.healthy(0) || rpm_sensor.healthy(1)) {
if (should_log(MASK_LOG_RC)) {
DataFlash.Log_Write_RPM(rpm_sensor);
}
}
}

View File

@ -138,6 +138,8 @@ void Plane::init_ardupilot()
// initialise battery monitoring
battery.init();
rpm_sensor.init();
// init the GCS
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console, 0);