forked from Archive/PX4-Autopilot
pwm_out: cleanup and prep for linux compatibility
This commit is contained in:
parent
10f4a2e91f
commit
990d7c159d
|
@ -4,19 +4,6 @@
|
|||
#
|
||||
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||
#
|
||||
|
||||
if ! ver hwcmp OMNIBUS_F4SD
|
||||
then
|
||||
if ! ver hwcmp BITCRAZE_CRAZYFLIE
|
||||
then
|
||||
# Configure all I2C buses to 100 KHz as they
|
||||
# are all external or slow
|
||||
# TODO: move this
|
||||
pwm_out i2c 1 100000
|
||||
pwm_out i2c 2 100000
|
||||
fi
|
||||
fi
|
||||
|
||||
###############################################################################
|
||||
# Begin Optional drivers #
|
||||
###############################################################################
|
||||
|
|
|
@ -5,14 +5,6 @@
|
|||
|
||||
board_adc start
|
||||
|
||||
# We know there are sketchy boards out there
|
||||
# as chinese companies produce Pixracers without
|
||||
# fully understanding the critical parts of the
|
||||
# schematic and BOM, leading to sensor brownouts
|
||||
# on boot. Original Pixracers following the
|
||||
# open hardware design do not require this.
|
||||
pwm_out sensor_reset 50
|
||||
|
||||
# Internal SPI
|
||||
ms5611 -s start
|
||||
|
||||
|
|
|
@ -7,9 +7,6 @@
|
|||
# IFO
|
||||
if param compare SYS_AUTOSTART 4071
|
||||
then
|
||||
# Change rate to 400 Khz for fast barometer
|
||||
#pwm_out i2c 1 400000
|
||||
|
||||
# IFO has only external i2c barometer.
|
||||
# It does not start EKF2 in the beginning which is strange behaviour. but 3 seconds hack.
|
||||
# We intentionally put this initialization to here for delayed initialization.
|
||||
|
|
|
@ -222,11 +222,6 @@ int PWMOut::set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_
|
|||
return OK;
|
||||
}
|
||||
|
||||
int PWMOut::set_i2c_bus_clock(unsigned bus, unsigned clock_hz)
|
||||
{
|
||||
return device::I2C::set_bus_clock(bus, clock_hz);
|
||||
}
|
||||
|
||||
void PWMOut::update_current_rate()
|
||||
{
|
||||
/*
|
||||
|
@ -695,7 +690,7 @@ void PWMOut::update_params()
|
|||
_num_disarmed_set = num_disarmed_set;
|
||||
}
|
||||
|
||||
int PWMOut::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
int PWMOut::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = pwm_ioctl(filp, cmd, arg);
|
||||
|
||||
|
@ -707,7 +702,7 @@ int PWMOut::ioctl(file *filp, int cmd, unsigned long arg)
|
|||
return ret;
|
||||
}
|
||||
|
||||
int PWMOut::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
|
@ -1094,34 +1089,6 @@ int PWMOut::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
return ret;
|
||||
}
|
||||
|
||||
void PWMOut::sensor_reset(int ms)
|
||||
{
|
||||
if (ms < 1) {
|
||||
ms = 1;
|
||||
}
|
||||
|
||||
board_spi_reset(ms, 0xffff);
|
||||
}
|
||||
|
||||
void PWMOut::peripheral_reset(int ms)
|
||||
{
|
||||
if (ms < 1) {
|
||||
ms = 10;
|
||||
}
|
||||
|
||||
board_peripheral_reset(ms);
|
||||
}
|
||||
|
||||
namespace
|
||||
{
|
||||
|
||||
int fmu_new_i2c_speed(unsigned bus, unsigned clock_hz)
|
||||
{
|
||||
return PWMOut::set_i2c_bus_clock(bus, clock_hz);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
int PWMOut::test(const char *dev)
|
||||
{
|
||||
int fd;
|
||||
|
@ -1267,50 +1234,6 @@ int PWMOut::custom_command(int argc, char *argv[])
|
|||
|
||||
const char *verb = argv[myoptind];
|
||||
|
||||
/* does not operate on a FMU instance */
|
||||
if (!strcmp(verb, "i2c")) {
|
||||
if (argc > 2) {
|
||||
int bus = strtol(argv[1], 0, 0);
|
||||
int clock_hz = strtol(argv[2], 0, 0);
|
||||
int ret = fmu_new_i2c_speed(bus, clock_hz);
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("setting I2C clock failed");
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
return print_usage("not enough arguments");
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "sensor_reset")) {
|
||||
if (argc > 1) {
|
||||
int reset_time = strtol(argv[1], nullptr, 0);
|
||||
sensor_reset(reset_time);
|
||||
|
||||
} else {
|
||||
sensor_reset(0);
|
||||
PX4_INFO("reset default time");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "peripheral_reset")) {
|
||||
if (argc > 2) {
|
||||
int reset_time = strtol(argv[2], 0, 0);
|
||||
peripheral_reset(reset_time);
|
||||
|
||||
} else {
|
||||
peripheral_reset(0);
|
||||
PX4_INFO("reset default time");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/* start pwm_out if not running */
|
||||
if (!is_running()) {
|
||||
|
||||
|
@ -1394,15 +1317,6 @@ By default the module runs on a work queue with a callback on the uORB actuator_
|
|||
|
||||
PRINT_MODULE_USAGE_NAME("pwm_out", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("sensor_reset", "Do a sensor reset (SPI bus)");
|
||||
PRINT_MODULE_USAGE_ARG("<ms>", "Delay time in ms between reset and re-enabling", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("peripheral_reset", "Reset board peripherals");
|
||||
PRINT_MODULE_USAGE_ARG("<ms>", "Delay time in ms between reset and re-enabling", true);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("i2c", "Configure I2C clock rate");
|
||||
PRINT_MODULE_USAGE_ARG("<bus_id> <rate>", "Specify the bus id (>=0) and rate in Hz", false);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test outputs");
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
|
|
|
@ -37,8 +37,8 @@
|
|||
#include <math.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_mixer.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
@ -103,9 +103,9 @@ public:
|
|||
|
||||
static int test(const char *dev);
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
|
||||
|
||||
virtual int init();
|
||||
int init() override;
|
||||
|
||||
uint32_t get_pwm_mask() const { return _pwm_mask; }
|
||||
void set_pwm_mask(uint32_t mask) { _pwm_mask = mask; }
|
||||
|
@ -113,8 +113,6 @@ public:
|
|||
unsigned get_alt_rate() const { return _pwm_alt_rate; }
|
||||
unsigned get_default_rate() const { return _pwm_default_rate; }
|
||||
|
||||
static int set_i2c_bus_clock(unsigned bus, unsigned clock_hz);
|
||||
|
||||
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
unsigned num_outputs, unsigned num_control_groups_updated) override;
|
||||
|
||||
|
@ -158,15 +156,12 @@ private:
|
|||
|
||||
void update_current_rate();
|
||||
int set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
|
||||
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
int pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
bool update_pwm_out_state(bool on);
|
||||
|
||||
void update_params();
|
||||
|
||||
static void sensor_reset(int ms);
|
||||
static void peripheral_reset(int ms);
|
||||
|
||||
PWMOut(const PWMOut &) = delete;
|
||||
PWMOut operator=(const PWMOut &) = delete;
|
||||
|
||||
|
|
Loading…
Reference in New Issue