Plane: added internal combustion engine support

this allows for automatic engine start and restart
This commit is contained in:
Andrew Tridgell 2016-07-23 17:37:42 +10:00
parent db8bf48747
commit 327a057ee0
8 changed files with 47 additions and 1 deletions

View File

@ -60,6 +60,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(barometer_accumulate, 50, 150),
SCHED_TASK(update_notify, 50, 300),
SCHED_TASK(read_rangefinder, 50, 100),
SCHED_TASK(ice_update, 10, 100),
SCHED_TASK(compass_cal_update, 50, 50),
SCHED_TASK(accel_cal_update, 10, 50),
#if OPTFLOW == ENABLED

View File

@ -1256,6 +1256,13 @@ void Plane::set_servos(void)
}
}
uint8_t override_pct;
if (g2.ice_control.throttle_override(override_pct)) {
// the ICE controller wants to override the throttle for starting
channel_throttle->set_servo_out(override_pct);
channel_throttle->calc_pwm();
}
// send values to the PWM timers for output
// ----------------------------------------
if (g.rudder_only == 0) {

View File

@ -1678,6 +1678,14 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_DO_ENGINE_CONTROL:
if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) {
result = MAV_RESULT_FAILED;
} else {
result = MAV_RESULT_ACCEPTED;
}
break;
default:
break;
}

View File

@ -1373,9 +1373,19 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/AP_Button/AP_Button.cpp
AP_SUBGROUPINFO(button, "BTN_", 1, ParametersG2, AP_Button),
// @Group: ICE_
// @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp
AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine),
AP_GROUPEND
};
ParametersG2::ParametersG2(void) :
ice_control(plane.rpm_sensor, plane.ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
}
/*
This is a conversion table from old parameter values to new
parameter names. The startup code looks for saved values of the old

View File

@ -574,13 +574,16 @@ public:
*/
class ParametersG2 {
public:
ParametersG2(void) { AP_Param::setup_object_defaults(this, var_info); }
ParametersG2(void);
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
// button reporting library
AP_Button button;
// internal combustion engine control
AP_ICEngine ice_control;
};
extern const AP_Param::Info var_info[];

View File

@ -89,6 +89,7 @@
#include <AP_Parachute/AP_Parachute.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_Button/AP_Button.h>
#include <AP_ICEngine/AP_ICEngine.h>
#include "GCS_Mavlink.h"
#include "quadplane.h"
@ -132,6 +133,7 @@ class Plane : public AP_HAL::HAL::Callbacks {
public:
friend class GCS_MAVLINK_Plane;
friend class Parameters;
friend class ParametersG2;
friend class AP_Arming_Plane;
friend class QuadPlane;
friend class AP_Tuning_Plane;
@ -956,6 +958,7 @@ private:
void read_receiver_rssi(void);
void rpm_update(void);
void button_update(void);
void ice_update(void);
void report_radio();
void report_ins();
void report_compass();

View File

@ -225,6 +225,12 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_DO_VTOL_TRANSITION:
plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state);
break;
case MAV_CMD_DO_ENGINE_CONTROL:
plane.ice_control.engine_control(cmd.content.do_engine_control.start_control,
cmd.content.do_engine_control.cold_start,
cmd.content.do_engine_control.height_delay_cm*0.01f);
break;
}
return true;

View File

@ -164,3 +164,11 @@ void Plane::button_update(void)
{
g2.button.update();
}
/*
update AP_ICEngine
*/
void Plane::ice_update(void)
{
g2.ice_control.update();
}