Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BoardConfig/IMU_heater.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15control IMU heater16*/1718#include <AP_HAL/AP_HAL.h>19#include <AP_Math/AP_Math.h>20#include <AP_IOMCU/AP_IOMCU.h>21#include <AP_Logger/AP_Logger.h>22#include <GCS_MAVLink/GCS.h>23#include "AP_BoardConfig.h"2425#if HAL_HAVE_IMU_HEATER2627extern const AP_HAL::HAL& hal;2829#ifndef HAL_HEATER_GPIO_ON30#define HAL_HEATER_GPIO_ON 131#endif3233void AP_BoardConfig::set_imu_temp(float current)34{35int8_t target = heater.imu_target_temperature.get();36// pass to HAL for Linux37hal.util->set_imu_target_temp((int8_t *)&heater.imu_target_temperature);38hal.util->set_imu_temp(current);3940if (target == -1) {41// nothing to do, make sure heater is left off42#if defined(HAL_HEATER_GPIO_PIN)43hal.gpio->write(HAL_HEATER_GPIO_PIN, !HAL_HEATER_GPIO_ON);44#endif45#if defined(HAL_HEATER2_GPIO_PIN)46hal.gpio->write(HAL_HEATER2_GPIO_PIN, !HAL_HEATER_GPIO_ON);47#endif48return;49}505152// limit to 65 degrees to prevent damage53target = constrain_int16(target, -1, 65);5455// average over temperatures to remove noise56heater.count++;57heater.sum += current;5859// update at 10Hz60uint32_t now = AP_HAL::millis();61if (now - heater.last_update_ms < 100) {62#if defined(HAL_HEATER_GPIO_PIN)63// output as duty cycle to local pin. Use a random sequence to64// prevent a periodic change to magnetic field65bool heater_on = (get_random16() < uint32_t(heater.output) * 0xFFFFU / 100U);66hal.gpio->write(HAL_HEATER_GPIO_PIN, heater_on?HAL_HEATER_GPIO_ON : !HAL_HEATER_GPIO_ON);67#if defined(HAL_HEATER2_GPIO_PIN)68hal.gpio->write(HAL_HEATER2_GPIO_PIN, heater_on?HAL_HEATER_GPIO_ON : !HAL_HEATER_GPIO_ON);69#endif70#endif71return;72}73float dt = (now - heater.last_update_ms) * 0.001;74dt = constrain_float(dt, 0, 0.5);7576heater.last_update_ms = now;7778heater.temperature = heater.sum / heater.count;79heater.sum = 0;80heater.count = 0;8182if (target < 0) {83heater.output = 0;84} else {85heater.output = heater.pi_controller.update(heater.temperature, target, dt);86heater.output = constrain_float(heater.output, 0, 100);87}8889#if HAL_LOGGING_ENABLED90if (now - heater.last_log_ms >= 1000) {91// @LoggerMessage: HEAT92// @Description: IMU Heater data93// @Field: TimeUS: Time since system startup94// @Field: Temp: Current IMU temperature95// @Field: Targ: Target IMU temperature96// @Field: P: Proportional portion of response97// @Field: I: Integral portion of response98// @Field: Out: Controller output to heating element99AP::logger().WriteStreaming("HEAT", "TimeUS,Temp,Targ,P,I,Out", "Qfbfff",100AP_HAL::micros64(),101heater.temperature, target,102heater.pi_controller.get_P(),103heater.pi_controller.get_I(),104heater.output);105heater.last_log_ms = now;106}107#endif // HAL_LOGGING_ENABLED108109#if 0110GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Heater: Out=%.1f Temp=%.1f",111double(heater.output),112double(avg));113#endif114115#if HAL_WITH_IO_MCU116if (io_enabled()) {117AP_IOMCU *iomcu = AP::iomcu();118if (iomcu) {119// tell IOMCU to setup heater120iomcu->set_heater_duty_cycle(heater.output);121}122}123#endif124}125126// getter for current temperature, return false if heater disabled127bool AP_BoardConfig::get_board_heater_temperature(float &temperature) const128{129if (heater.imu_target_temperature == -1) {130return false; // heater disabled131}132temperature = heater.temperature;133return true;134}135136// getter for min arming temperature, return false if heater disabled or min check disabled137bool AP_BoardConfig::get_board_heater_arming_temperature(int8_t &temperature) const138{139if ((heater.imu_target_temperature == -1) || (heater.imu_arming_temperature_margin_low == 0)) {140return false; // heater or temperature check disabled141}142temperature = heater.imu_target_temperature - heater.imu_arming_temperature_margin_low;143return true;144}145146#endif // HAL_HAVE_IMU_HEATER147148149