mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: added a new RPM driver based on ESC telem
this adds a new RPM driver based on average RPM of selected motors. A new bitmask parameter has been added to select which motor to average.
This commit is contained in:
parent
b4d54cf565
commit
cdc874c366
|
@ -18,6 +18,7 @@
|
|||
#include "RPM_SITL.h"
|
||||
#include "RPM_EFI.h"
|
||||
#include "RPM_HarmonicNotch.h"
|
||||
#include "RPM_ESC_Telem.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -26,7 +27,7 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||
// @Param: _TYPE
|
||||
// @DisplayName: RPM type
|
||||
// @Description: What type of RPM sensor is connected
|
||||
// @Values: 0:None,1:PWM,2:AUXPIN,3:EFI,4:Harmonic Notch
|
||||
// @Values: 0:None,1:PWM,2:AUXPIN,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_TYPE", 0, AP_RPM, _type[0], 0),
|
||||
|
||||
|
@ -65,11 +66,18 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("_PIN", 5, AP_RPM, _pin[0], 54),
|
||||
|
||||
// @Param: _ESC_MASK
|
||||
// @DisplayName: Bitmask of ESC telemetry channels to average
|
||||
// @Description: Mask of channels which support ESC rpm telemetry. RPM telemetry of the selected channels will be averaged
|
||||
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_ESC_MASK", 6, AP_RPM, _esc_mask[0], 0),
|
||||
|
||||
#if RPM_MAX_INSTANCES > 1
|
||||
// @Param: 2_TYPE
|
||||
// @DisplayName: Second RPM type
|
||||
// @Description: What type of RPM sensor is connected
|
||||
// @Values: 0:None,1:PWM,2:AUXPIN,3:EFI,4:Harmonic Notch
|
||||
// @Values: 0:None,1:PWM,2:AUXPIN,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_TYPE", 10, AP_RPM, _type[1], 0),
|
||||
|
||||
|
@ -86,6 +94,13 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||
// @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("2_PIN", 12, AP_RPM, _pin[1], -1),
|
||||
|
||||
// @Param: 2_ESC_MASK
|
||||
// @DisplayName: Bitmask of ESC telemetry channels to average
|
||||
// @Description: Mask of channels which support ESC rpm telemetry. RPM telemetry of the selected channels will be averaged
|
||||
// @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_ESC_MASK", 13, AP_RPM, _esc_mask[1], 0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
|
@ -111,31 +126,33 @@ void AP_RPM::init(void)
|
|||
return;
|
||||
}
|
||||
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
||||
uint8_t type = _type[i];
|
||||
switch (_type[i]) {
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
if (type == RPM_TYPE_PWM) {
|
||||
case RPM_TYPE_PWM:
|
||||
case RPM_TYPE_PIN:
|
||||
// PWM option same as PIN option, for upgrade
|
||||
type = RPM_TYPE_PIN;
|
||||
}
|
||||
if (type == RPM_TYPE_PIN) {
|
||||
drivers[i] = new AP_RPM_Pin(*this, i, state[i]);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case RPM_TYPE_ESC_TELEM:
|
||||
drivers[i] = new AP_RPM_ESC_Telem(*this, i, state[i]);
|
||||
break;
|
||||
#if HAL_EFI_ENABLED
|
||||
if (type == RPM_TYPE_EFI) {
|
||||
case RPM_TYPE_EFI:
|
||||
drivers[i] = new AP_RPM_EFI(*this, i, state[i]);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
// include harmonic notch last
|
||||
// this makes whatever process is driving the dynamic notch appear as an RPM value
|
||||
if (type == RPM_TYPE_HNTCH) {
|
||||
case RPM_TYPE_HNTCH:
|
||||
drivers[i] = new AP_RPM_HarmonicNotch(*this, i, state[i]);
|
||||
}
|
||||
break;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (type == RPM_TYPE_SITL) {
|
||||
case RPM_TYPE_SITL:
|
||||
drivers[i] = new AP_RPM_SITL(*this, i, state[i]);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
if (drivers[i] != nullptr) {
|
||||
// we loaded a driver for this instance, so it must be
|
||||
// present (although it may not be healthy)
|
||||
|
|
|
@ -42,6 +42,7 @@ public:
|
|||
RPM_TYPE_PIN = 2,
|
||||
RPM_TYPE_EFI = 3,
|
||||
RPM_TYPE_HNTCH = 4,
|
||||
RPM_TYPE_ESC_TELEM = 5,
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
RPM_TYPE_SITL = 10,
|
||||
#endif
|
||||
|
@ -62,6 +63,7 @@ public:
|
|||
AP_Float _maximum[RPM_MAX_INSTANCES];
|
||||
AP_Float _minimum[RPM_MAX_INSTANCES];
|
||||
AP_Float _quality_min[RPM_MAX_INSTANCES];
|
||||
AP_Int32 _esc_mask[RPM_MAX_INSTANCES];
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
|
@ -0,0 +1,42 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_ESC_Telem/AP_ESC_Telem.h>
|
||||
|
||||
#include "RPM_ESC_Telem.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
open the sensor in constructor
|
||||
*/
|
||||
AP_RPM_ESC_Telem::AP_RPM_ESC_Telem(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
|
||||
AP_RPM_Backend(_ap_rpm, _instance, _state)
|
||||
{
|
||||
instance = _instance;
|
||||
}
|
||||
|
||||
|
||||
void AP_RPM_ESC_Telem::update(void)
|
||||
{
|
||||
#ifdef HAL_WITH_ESC_TELEM
|
||||
AP_ESC_Telem &esc_telem = AP::esc_telem();
|
||||
float esc_rpm = esc_telem.get_average_motor_rpm(ap_rpm._esc_mask[state.instance]);
|
||||
state.rate_rpm = esc_rpm * ap_rpm._scaling[state.instance];
|
||||
state.signal_quality = 0.5f;
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_RPM.h"
|
||||
#include "RPM_Backend.h"
|
||||
|
||||
class AP_RPM_ESC_Telem : public AP_RPM_Backend
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
AP_RPM_ESC_Telem(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
|
||||
|
||||
// update state
|
||||
void update(void) override;
|
||||
private:
|
||||
uint8_t instance;
|
||||
};
|
Loading…
Reference in New Issue