mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
159 lines
4.3 KiB
C++
159 lines
4.3 KiB
C++
/****************************************************************************
|
|
*
|
|
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
|
*
|
|
* Redistribution and use in source and binary forms, with or without
|
|
* modification, are permitted provided that the following conditions
|
|
* are met:
|
|
*
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
* notice, this list of conditions and the following disclaimer.
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
* notice, this list of conditions and the following disclaimer in
|
|
* the documentation and/or other materials provided with the
|
|
* distribution.
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
* used to endorse or promote products derived from this software
|
|
* without specific prior written permission.
|
|
*
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
*
|
|
****************************************************************************/
|
|
|
|
#include "BatterySimulator.hpp"
|
|
|
|
BatterySimulator::BatterySimulator() :
|
|
ModuleParams(nullptr),
|
|
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
|
|
_battery(1, this, BATTERY_SIMLATOR_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
|
{
|
|
}
|
|
|
|
BatterySimulator::~BatterySimulator()
|
|
{
|
|
perf_free(_loop_perf);
|
|
}
|
|
|
|
bool BatterySimulator::init()
|
|
{
|
|
ScheduleOnInterval(BATTERY_SIMLATOR_SAMPLE_INTERVAL_US);
|
|
return true;
|
|
}
|
|
|
|
void BatterySimulator::Run()
|
|
{
|
|
if (should_exit()) {
|
|
ScheduleClear();
|
|
exit_and_cleanup();
|
|
return;
|
|
}
|
|
|
|
perf_begin(_loop_perf);
|
|
|
|
// Check if parameters have changed
|
|
if (_parameter_update_sub.updated()) {
|
|
// clear update
|
|
parameter_update_s param_update;
|
|
_parameter_update_sub.copy(¶m_update);
|
|
|
|
updateParams();
|
|
}
|
|
|
|
if (_vehicle_status_sub.updated()) {
|
|
vehicle_status_s vehicle_status;
|
|
|
|
if (_vehicle_status_sub.copy(&vehicle_status)) {
|
|
_armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
|
|
}
|
|
}
|
|
|
|
const hrt_abstime now_us = hrt_absolute_time();
|
|
|
|
const float discharge_interval_us = _param_sim_bat_drain.get() * 1000 * 1000;
|
|
|
|
if (_armed) {
|
|
if (_last_integration_us != 0) {
|
|
_battery_percentage -= (now_us - _last_integration_us) / discharge_interval_us;
|
|
}
|
|
|
|
_last_integration_us = now_us;
|
|
|
|
} else {
|
|
_last_integration_us = 0;
|
|
}
|
|
|
|
float ibatt = -1.0f; // no current sensor in simulation
|
|
|
|
_battery_percentage = math::max(_battery_percentage, _param_bat_min_pct.get() / 100.f);
|
|
float vbatt = math::gradual(_battery_percentage, 0.f, 1.f, _battery.empty_cell_voltage(), _battery.full_cell_voltage());
|
|
vbatt *= _battery.cell_count();
|
|
|
|
_battery.updateBatteryStatus(now_us, vbatt, ibatt, true);
|
|
|
|
perf_end(_loop_perf);
|
|
}
|
|
|
|
int BatterySimulator::task_spawn(int argc, char *argv[])
|
|
{
|
|
BatterySimulator *instance = new BatterySimulator();
|
|
|
|
if (instance) {
|
|
_object.store(instance);
|
|
_task_id = task_id_is_work_queue;
|
|
|
|
if (instance->init()) {
|
|
return PX4_OK;
|
|
}
|
|
|
|
} else {
|
|
PX4_ERR("alloc failed");
|
|
}
|
|
|
|
delete instance;
|
|
_object.store(nullptr);
|
|
_task_id = -1;
|
|
|
|
return PX4_ERROR;
|
|
}
|
|
|
|
int BatterySimulator::custom_command(int argc, char *argv[])
|
|
{
|
|
return print_usage("unknown command");
|
|
}
|
|
|
|
int BatterySimulator::print_usage(const char *reason)
|
|
{
|
|
if (reason) {
|
|
PX4_WARN("%s\n", reason);
|
|
}
|
|
|
|
PRINT_MODULE_DESCRIPTION(
|
|
R"DESCR_STR(
|
|
### Description
|
|
|
|
|
|
)DESCR_STR");
|
|
|
|
PRINT_MODULE_USAGE_NAME("battery_simulator", "system");
|
|
PRINT_MODULE_USAGE_COMMAND("start");
|
|
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
|
|
|
return 0;
|
|
}
|
|
|
|
extern "C" __EXPORT int battery_simulator_main(int argc, char *argv[])
|
|
{
|
|
return BatterySimulator::main(argc, argv);
|
|
}
|