Browse Source

heater: px4io: Add support for heaters on IO MCU

release/1.12
JacobCrabill 5 years ago committed by Lorenz Meier
parent
commit
8e8497ff77
  1. 6
      boards/px4/fmu-v3/src/board_config.h
  2. 65
      src/drivers/drv_io_heater.h
  3. 78
      src/drivers/heater/heater.cpp
  4. 28
      src/drivers/heater/heater.h
  5. 15
      src/drivers/px4io/px4io.cpp

6
boards/px4/fmu-v3/src/board_config.h

@ -168,6 +168,12 @@ @@ -168,6 +168,12 @@
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
/* Internal IMU Heater
*
* Connected to the IO MCU; tell compiler to enable support
*/
#define PX4IO_HEATER_ENABLED
__BEGIN_DECLS
/****************************************************************************************************

65
src/drivers/drv_io_heater.h

@ -0,0 +1,65 @@ @@ -0,0 +1,65 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file drv_io_heater.h
*
* IO IMU heater control interface (PX4IO)
*/
#ifndef _DRV_IO_HEATER_H
#define _DRV_IO_HEATER_H
#include <stdint.h>
#include <sys/ioctl.h>
/*
* ioctl() definitions
*/
#define IO_HEATER_DEVICE_PATH "/dev/px4io"
#define _IO_HEATER_BASE (0x2e00)
#define PX4IO_HEATER_CONTROL _PX4_IOC(_IO_HEATER_BASE, 0)
/* ... to IOX_SET_VALUE + 8 */
/* enum passed to IO_HEATER_CONTROL ioctl()*/
enum IO_HEATER_MODE {
HEATER_MODE_OFF = 0,
HEATER_MODE_ON = 1,
HEATER_MODE_DISABLED = -1
};
#endif

78
src/drivers/heater/heater.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2018-19 PX4 Development Team. All rights reserved.
* Copyright (c) 2018-20 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
@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
* @author Alex Klimaj <alexklimaj@gmail.com>
* @author Jake Dahl <dahl.jakejacob@gmail.com>
* @author Mohammed Kabir <mhkabir@mit.edu>
* @author Jacob Crabill <jacob@flyvoly.com>
*/
#include "heater.h"
@ -45,23 +46,86 @@ @@ -45,23 +46,86 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/log.h>
#include <drivers/drv_hrt.h>
#ifndef GPIO_HEATER_OUTPUT
#error "To use the heater driver, the board_config.h must define and initialize GPIO_HEATER_OUTPUT"
#include <drivers/drv_io_heater.h>
#if defined(BOARD_USES_PX4IO) and defined(PX4IO_HEATER_ENABLED)
// Heater on some boards is on IO MCU
// Use ioctl calls to IO driver to turn heater on/off
# define HEATER_PX4IO
#else
// Use direct calls to turn GPIO pin on/off
# ifndef GPIO_HEATER_OUTPUT
# error "To use the heater driver, the board_config.h must define and initialize GPIO_HEATER_OUTPUT"
# endif
# define HEATER_GPIO
#endif
Heater::Heater() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
{
#ifdef HEATER_PX4IO
_io_fd = px4_open(IO_HEATER_DEVICE_PATH, O_RDWR);
if (_io_fd < 0) {
PX4_ERR("Unable to open heater device path");
return;
}
#endif
// Initialize heater to off state
px4_arch_configgpio(GPIO_HEATER_OUTPUT);
heater_enable();
}
Heater::~Heater()
{
// Reset heater to off state
heater_disable();
#ifdef HEATER_PX4IO
px4_close(_io_fd);
#endif
}
void Heater::heater_enable()
{
#ifdef HEATER_PX4IO
px4_ioctl(_io_fd, PX4IO_HEATER_CONTROL, HEATER_MODE_OFF);
#endif
#ifdef HEATER_GPIO
px4_arch_configgpio(GPIO_HEATER_OUTPUT);
#endif
}
void Heater::heater_disable()
{
#ifdef HEATER_PX4IO
px4_ioctl(_io_fd, PX4IO_HEATER_CONTROL, HEATER_MODE_DISABLED);
#endif
#ifdef HEATER_GPIO
px4_arch_configgpio(GPIO_HEATER_OUTPUT);
#endif
}
void Heater::heater_on()
{
#ifdef HEATER_PX4IO
px4_ioctl(_io_fd, PX4IO_HEATER_CONTROL, HEATER_MODE_ON);
#endif
#ifdef HEATER_GPIO
px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, 1);
#endif
}
void Heater::heater_off()
{
#ifdef HEATER_PX4IO
px4_ioctl(_io_fd, PX4IO_HEATER_CONTROL, HEATER_MODE_OFF);
#endif
#ifdef HEATER_GPIO
px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, 0);
#endif
}
int Heater::custom_command(int argc, char *argv[])
@ -84,7 +148,7 @@ void Heater::Run() @@ -84,7 +148,7 @@ void Heater::Run()
if (_heater_on) {
// Turn the heater off.
px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, 0);
heater_off();
_heater_on = false;
} else {
@ -115,7 +179,7 @@ void Heater::Run() @@ -115,7 +179,7 @@ void Heater::Run()
// Turn the heater on.
_heater_on = true;
px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, 1);
heater_on();
}
// Schedule the next cycle.

28
src/drivers/heater/heater.h

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
* Copyright (c) 2018-20 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
@ -37,6 +37,7 @@ @@ -37,6 +37,7 @@
* @author Mark Sauder <mcsauder@gmail.com>
* @author Alex Klimaj <alexklimaj@gmail.com>
* @author Jake Dahl <dahl.jakejacob@gmail.com>
* @author Jacob Crabill <jacob@flyvoly.com>
*/
#pragma once
@ -165,9 +166,34 @@ private: @@ -165,9 +166,34 @@ private:
*/
void update_params(const bool force = false);
/**
* @brief Enables / configures the heater (either by GPIO or PX4IO)
*/
void heater_enable();
/**
* @brief Disnables the heater (either by GPIO or PX4IO)
*/
void heater_disable();
/**
* @brief Turns the heater on (either by GPIO or PX4IO)
*/
void heater_on();
/**
* @brief Turns the heater off (either by GPIO or PX4IO)
*/
void heater_off();
/** Work queue struct for the RTOS scheduler. */
static struct work_s _work;
/** File descriptor for PX4IO for heater ioctl's */
#if defined(HEATER_PX4IO)
int _io_fd;
#endif
int _controller_period_usec = CONTROLLER_PERIOD_DEFAULT;
int _controller_time_on_usec = 0;

15
src/drivers/px4io/px4io.cpp

@ -65,6 +65,7 @@ @@ -65,6 +65,7 @@
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_sbus.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_io_heater.h>
#include <drivers/drv_mixer.h>
#include <rc/dsm.h>
@ -2931,6 +2932,20 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) @@ -2931,6 +2932,20 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
break;
case PX4IO_HEATER_CONTROL:
if (arg == (unsigned long)HEATER_MODE_DISABLED) {
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_THERMAL, PX4IO_THERMAL_IGNORE);
} else if (arg == 1) {
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_THERMAL, PX4IO_THERMAL_FULL);
} else {
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_THERMAL, PX4IO_THERMAL_OFF);
}
break;
default:
/* see if the parent class can make any use of it */
ret = CDev::ioctl(filep, cmd, arg);

Loading…
Cancel
Save