mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: added a SITL RPM backend
This commit is contained in:
parent
223ce2b6aa
commit
45ea2a9b68
|
@ -16,6 +16,7 @@
|
||||||
|
|
||||||
#include "AP_RPM.h"
|
#include "AP_RPM.h"
|
||||||
#include "RPM_PX4_PWM.h"
|
#include "RPM_PX4_PWM.h"
|
||||||
|
#include "RPM_SITL.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -84,6 +85,11 @@ void AP_RPM::init(void)
|
||||||
state[instance].instance = instance;
|
state[instance].instance = instance;
|
||||||
drivers[instance] = new AP_RPM_PX4_PWM(*this, instance, state[instance]);
|
drivers[instance] = new AP_RPM_PX4_PWM(*this, instance, state[instance]);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
uint8_t instance = num_instances;
|
||||||
|
state[instance].instance = instance;
|
||||||
|
drivers[instance] = new AP_RPM_SITL(*this, instance, state[instance]);
|
||||||
#endif
|
#endif
|
||||||
if (drivers[i] != NULL) {
|
if (drivers[i] != NULL) {
|
||||||
// we loaded a driver for this instance, so it must be
|
// we loaded a driver for this instance, so it must be
|
||||||
|
|
|
@ -0,0 +1,47 @@
|
||||||
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
/*
|
||||||
|
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>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
#include "RPM_SITL.h"
|
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
/*
|
||||||
|
open the sensor in constructor
|
||||||
|
*/
|
||||||
|
AP_RPM_SITL::AP_RPM_SITL(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) :
|
||||||
|
AP_RPM_Backend(_ap_rpm, instance, _state)
|
||||||
|
{
|
||||||
|
sitl = (SITL::SITL *)AP_Param::find_object("SIM_");
|
||||||
|
instance = _instance;
|
||||||
|
}
|
||||||
|
|
||||||
|
void AP_RPM_SITL::update(void)
|
||||||
|
{
|
||||||
|
if (sitl == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (instance == 0) {
|
||||||
|
state.rate_rpm = sitl->state.rpm1;
|
||||||
|
} else {
|
||||||
|
state.rate_rpm = sitl->state.rpm2;
|
||||||
|
}
|
||||||
|
state.last_reading_ms = AP_HAL::millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
|
@ -0,0 +1,40 @@
|
||||||
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
/*
|
||||||
|
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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef AP_RPM_SITL_H
|
||||||
|
#define AP_RPM_SITL_H
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
||||||
|
#include "AP_RPM.h"
|
||||||
|
#include "RPM_Backend.h"
|
||||||
|
#include <SITL/SITL.h>
|
||||||
|
|
||||||
|
class AP_RPM_SITL : public AP_RPM_Backend
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
// constructor
|
||||||
|
AP_RPM_SITL(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state);
|
||||||
|
|
||||||
|
// update state
|
||||||
|
void update(void);
|
||||||
|
private:
|
||||||
|
SITL::SITL *sitl;
|
||||||
|
uint8_t instance;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
#endif // AP_RPM_SITL_H
|
Loading…
Reference in New Issue