delete drv_mixer.h

This commit is contained in:
Daniel Agar 2022-08-24 16:06:29 -04:00
parent d3312f955f
commit 0019ffbea6
20 changed files with 14 additions and 484 deletions

View File

@ -795,57 +795,6 @@ int ModalaiEsc::update_params()
return ret;
}
int ModalaiEsc::ioctl(file *filp, int cmd, unsigned long arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
PX4_DEBUG("modalai_esc ioctl cmd: %d, arg: %ld", cmd, arg);
switch (cmd) {
case PWM_SERVO_ARM:
PX4_INFO("PWM_SERVO_ARM");
break;
case PWM_SERVO_DISARM:
PX4_INFO("PWM_SERVO_DISARM");
break;
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
}
break;
default:
ret = -ENOTTY;
break;
}
/* if nobody wants it, let CDev have it */
if (ret == -ENOTTY) {
ret = CDev::ioctl(filp, cmd, arg);
}
return ret;
}
/* OutputModuleInterface */
void ModalaiEsc::mixerChanged()
{
/*
* This driver is only supporting 4 channel ESC
*/
}
void ModalaiEsc::updateLeds(vehicle_control_mode_s mode, led_control_s control)
{
int i = 0;

View File

@ -34,7 +34,6 @@
#pragma once
#include <drivers/device/device.h>
#include <drivers/drv_mixer.h>
#include <lib/cdev/CDev.hpp>
#include <lib/led/led.h>
#include <lib/mixer_module/mixer_module.hpp>
@ -80,8 +79,6 @@ public:
/** @see OutputModuleInterface */
void mixerChanged() override;
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual int init();
typedef enum {

View File

@ -1,88 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 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_mixer.h
*
* Mixer ioctl interfaces.
*
* Normal workflow is:
*
* - open mixer device
* - add mixer(s)
* loop:
* - mix actuators to array
*
* Each client has its own configuration.
*
* When mixing, outputs are produced by mixers in the order they are
* added. A simple mixer produces one output; a multirotor mixer will
* produce several outputs, etc.
*/
#ifndef _DRV_MIXER_H
#define _DRV_MIXER_H
#include <px4_platform_common/defines.h>
#include <stdint.h>
#include <sys/ioctl.h>
#define MIXER0_DEVICE_PATH "/dev/mixer0"
/*
* ioctl() definitions
*/
#define _MIXERIOCBASE (0x2500)
#define _MIXERIOC(_n) (_PX4_IOC(_MIXERIOCBASE, _n))
/* _MIXERIOC(0) was deprecated */
/** reset (clear) the mixer configuration */
#define MIXERIOCRESET _MIXERIOC(1)
/* _MIXERIOC(3) was deprecated */
/* _MIXERIOC(4) was deprecated */
/**
* Add mixer(s) from the buffer in (const char *)arg
*/
#define MIXERIOCLOADBUF _MIXERIOC(5)
/*
* XXX Thoughts for additional operations:
*
* - get/set output scale, for tuning center/limit values.
* - save/serialise for saving tuned mixers.
*/
#endif /* _DRV_MIXER_H */

View File

@ -41,7 +41,6 @@ char DShot::_telemetry_device[] {};
px4::atomic_bool DShot::_request_telemetry_init{false};
DShot::DShot() :
CDev("/dev/dshot"),
OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default)
{
_mixing_output.setAllDisarmedValues(DSHOT_DISARM_VALUE);
@ -59,32 +58,13 @@ DShot::~DShot()
// make sure outputs are off
up_dshot_arm(false);
// clean up the alternate device node
unregister_class_devname(PWM_OUTPUT_BASE_DEVICE_PATH, _class_instance);
perf_free(_cycle_perf);
delete _telemetry;
}
int DShot::init()
{
// do regular cdev init
int ret = CDev::init();
if (ret != OK) {
return ret;
}
// try to claim the generic PWM output device node as well - it's OK if we fail at this
_class_instance = register_class_devname(PWM_OUTPUT_BASE_DEVICE_PATH);
if (_class_instance == CLASS_DEVICE_PRIMARY) {
// lets not be too verbose
} else if (_class_instance < 0) {
PX4_ERR("FAILED registering class device");
}
_mixing_output.setDriverInstance(_class_instance);
_mixing_output.setDriverInstance(0);
_output_mask = (1u << _num_outputs) - 1;
@ -486,8 +466,6 @@ void DShot::Run()
return;
}
SmartLock lock_guard(_lock);
perf_begin(_cycle_perf);
_mixing_output.update();
@ -645,40 +623,6 @@ void DShot::update_params()
}
}
int DShot::ioctl(file *filp, int cmd, unsigned long arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
PX4_DEBUG("dshot ioctl cmd: %d, arg: %ld", cmd, arg);
switch (cmd) {
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
break;
}
default:
ret = -ENOTTY;
break;
}
// if nobody wants it, let CDev have it
if (ret == -ENOTTY) {
ret = CDev::ioctl(filp, cmd, arg);
}
return ret;
}
int DShot::custom_command(int argc, char *argv[])
{
const char *verb = argv[0];

View File

@ -34,7 +34,6 @@
#include <drivers/device/device.h>
#include <drivers/drv_input_capture.h>
#include <drivers/drv_mixer.h>
#include <lib/mixer_module/mixer_module.hpp>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
@ -60,7 +59,7 @@ static constexpr int DSHOT_DISARM_VALUE = 0;
static constexpr int DSHOT_MIN_THROTTLE = 1;
static constexpr int DSHOT_MAX_THROTTLE = 1999;
class DShot : public cdev::CDev, public ModuleBase<DShot>, public OutputModuleInterface
class DShot : public ModuleBase<DShot>, public OutputModuleInterface
{
public:
DShot();
@ -71,8 +70,6 @@ public:
virtual int init();
virtual int ioctl(file *filp, int cmd, unsigned long arg);
void mixerChanged() override;
/** @see ModuleBase::print_status() */
@ -166,8 +163,6 @@ private:
static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS};
uint32_t _output_mask{0};
int _class_instance{-1};
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};
Command _current_command{};

View File

@ -318,39 +318,6 @@ void LinuxPWMOut::update_params()
}
}
int LinuxPWMOut::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
PX4_DEBUG("ioctl cmd: %d, arg: %ld", cmd, arg);
switch (cmd) {
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
update_params();
break;
}
default:
ret = -ENOTTY;
break;
}
if (ret == -ENOTTY) {
ret = CDev::ioctl(filp, cmd, arg);
}
return ret;
}
int LinuxPWMOut::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");

View File

@ -35,7 +35,6 @@
#include <drivers/device/device.h>
#include <drivers/drv_mixer.h>
#include <lib/cdev/CDev.hpp>
#include <lib/mathlib/mathlib.h>
#include <lib/mixer_module/mixer_module.hpp>

View File

@ -43,7 +43,6 @@
#include <lib/mixer_module/mixer_module.hpp>
#include <px4_platform_common/module.h>
#include <lib/perf/perf_counter.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_hrt.h>
#include <px4_platform_common/getopt.h>
@ -57,16 +56,14 @@
using namespace drv_pca9685_pwm;
using namespace time_literals;
class PCA9685Wrapper : public cdev::CDev, public ModuleBase<PCA9685Wrapper>, public OutputModuleInterface
class PCA9685Wrapper : public ModuleBase<PCA9685Wrapper>, public OutputModuleInterface
{
public:
PCA9685Wrapper(int schd_rate_limit = 400);
~PCA9685Wrapper() override ;
int init() override;
int ioctl(cdev::file_t *filep, int cmd, unsigned long arg) override;
int init();
void mixerChanged() override;
@ -121,7 +118,6 @@ protected:
};
PCA9685Wrapper::PCA9685Wrapper(int schd_rate_limit) :
CDev(nullptr),
OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")),
_schd_rate_limit(schd_rate_limit)
@ -146,20 +142,12 @@ PCA9685Wrapper::~PCA9685Wrapper()
int PCA9685Wrapper::init()
{
int ret = CDev::init();
int ret = pca9685->init();
if (ret != PX4_OK) {
return ret;
}
ret = pca9685->init();
if (ret != PX4_OK) {
return ret;
}
_class_instance = register_class_devname(PWM_OUTPUT_BASE_DEVICE_PATH);
this->ChangeWorkQueue(px4::device_bus_to_wq(pca9685->get_device_id()));
PX4_INFO("running on I2C bus %d address 0x%.2x", pca9685->get_device_bus(), pca9685->get_device_address());
@ -379,7 +367,6 @@ void PCA9685Wrapper::Run()
if (should_exit()) {
ScheduleClear();
_mixing_output.unregister();
unregister_class_devname(PWM_OUTPUT_BASE_DEVICE_PATH, _class_instance);
pca9685->Stop();
delete pca9685;
@ -389,8 +376,6 @@ void PCA9685Wrapper::Run()
return;
}
SmartLock lock_guard(_lock);
perf_begin(_cycle_perf);
switch (_state) {
@ -466,49 +451,6 @@ void PCA9685Wrapper::Run()
perf_end(_cycle_perf);
}
int PCA9685Wrapper::ioctl(cdev::file_t *filep, int cmd, unsigned long arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
switch (cmd) {
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
break;
}
case PWM_SERVO_GET_COUNT:
*(unsigned *)arg = PCA9685_PWM_CHANNEL_COUNT;
break;
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
case PWM_SERVO_ARM:
case PWM_SERVO_DISARM:
break;
default:
ret = -ENOTTY;
break;
}
if (ret == -ENOTTY) {
ret = CDev::ioctl(filep, cmd, arg);
}
return ret;
}
int PCA9685Wrapper::print_usage(const char *reason)
{
if (reason) {
@ -550,7 +492,6 @@ int PCA9685Wrapper::print_status() {
pca9685->get_device_bus(),
pca9685->get_device_address(),
(double)(pca9685->getFrequency()));
PX4_INFO("CDev path: %s%d", PWM_OUTPUT_BASE_DEVICE_PATH, this->_class_instance);
return ret;
}
@ -623,16 +564,17 @@ int PCA9685Wrapper::task_spawn(int argc, char **argv) {
return PX4_ERROR;
}
void PCA9685Wrapper::mixerChanged() {
void PCA9685Wrapper::mixerChanged()
{
OutputModuleInterface::mixerChanged();
if (_mixing_output.mixers()) { // only update trims if mixer loaded
updatePWMParamTrim();
}
_mixing_output.updateSubscriptions(false);
}
extern "C" __EXPORT int pca9685_pwm_out_main(int argc, char *argv[]);
int pca9685_pwm_out_main(int argc, char *argv[]){
extern "C" __EXPORT int pca9685_pwm_out_main(int argc, char *argv[]){
return PCA9685Wrapper::main(argc, argv);
}

View File

@ -966,20 +966,6 @@ int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
*(unsigned *)arg = _num_outputs;
break;
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
update_params();
break;
}
default:
ret = -ENOTTY;
break;

View File

@ -40,7 +40,6 @@
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_pwm_output.h>
#include <lib/cdev/CDev.hpp>
#include <lib/mathlib/mathlib.h>

View File

@ -50,7 +50,6 @@
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_io_heater.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_sbus.h>
@ -1718,21 +1717,6 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
break;
}
case MIXERIOCRESET:
PX4_DEBUG("MIXERIOCRESET");
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
PX4_DEBUG("MIXERIOCLOADBUF");
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
break;
}
case PX4IO_SET_DEBUG:
PX4_DEBUG("PX4IO_SET_DEBUG");

View File

@ -413,33 +413,6 @@ void TAP_ESC::Run()
perf_end(_cycle_perf);
}
int TAP_ESC::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
SmartLock lock_guard(_lock);
int ret = OK;
switch (cmd) {
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
break;
}
default:
ret = -ENOTTY;
break;
}
return ret;
}
int TAP_ESC::task_spawn(int argc, char *argv[])
{
/* Parse arguments */

View File

@ -62,7 +62,6 @@
#include <uORB/topics/led_control.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include "tap_esc_common.h"
@ -100,7 +99,6 @@ public:
int print_status() override;
int init() override;
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated) override;

View File

@ -58,7 +58,6 @@
#include <uORB/topics/esc_status.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_pwm_output.h>
#include "uavcan_module.hpp"
@ -941,44 +940,6 @@ UavcanNode::enable_idle_throttle_when_armed(bool value)
}
}
int
UavcanNode::ioctl(file *filp, int cmd, unsigned long arg)
{
int ret = OK;
pthread_mutex_lock(&_node_mutex);
switch (cmd) {
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
break;
case MIXERIOCRESET:
_mixing_interface_esc.mixingOutput().resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_interface_esc.mixingOutput().loadMixer(buf, buflen);
}
break;
default:
ret = -ENOTTY;
break;
}
pthread_mutex_unlock(&_node_mutex);
if (ret == -ENOTTY) {
ret = CDev::ioctl(filp, cmd, arg);
}
return ret;
}
bool UavcanMixingInterfaceESC::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs,
unsigned num_control_groups_updated)
{
@ -998,18 +959,11 @@ void UavcanMixingInterfaceESC::mixerChanged()
{
int rotor_count = 0;
if (_mixing_output.useDynamicMixing()) {
for (unsigned i = 0; i < MAX_ACTUATORS; ++i) {
rotor_count += _mixing_output.isFunctionSet(i);
for (unsigned i = 0; i < MAX_ACTUATORS; ++i) {
rotor_count += _mixing_output.isFunctionSet(i);
if (i < esc_status_s::CONNECTED_ESC_MAX) {
_esc_controller.esc_status().esc[i].actuator_function = (uint8_t)_mixing_output.outputFunction(i);
}
}
} else {
if (_mixing_output.mixers()) {
rotor_count = _mixing_output.mixers()->get_multirotor_count();
if (i < esc_status_s::CONNECTED_ESC_MAX) {
_esc_controller.esc_status().esc[i].actuator_function = (uint8_t)_mixing_output.outputFunction(i);
}
}

View File

@ -178,8 +178,6 @@ public:
virtual ~UavcanNode();
virtual int ioctl(file *filp, int cmd, unsigned long arg);
static int start(uavcan::NodeID node_id, uint32_t bitrate);
uavcan::Node<> &get_node() { return _node; }

View File

@ -63,9 +63,5 @@
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
#define UAVCAN_ESC_DEVICE_PATH "/dev/uavcan/esc"
// ioctl interface
#define _UAVCAN_IOC(_n) (_IOC(_UAVCAN_IOCBASE, _n))
#define _UAVCAN_IOCBASE (0x4000) // IOCTL base for module UAVCAN
// public prototypes
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);

View File

@ -1204,43 +1204,3 @@ int MixingOutput::controlCallback(uintptr_t handle, uint8_t control_group, uint8
return 0;
}
void MixingOutput::resetMixer()
{
if (_mixers != nullptr) {
delete _mixers;
_mixers = nullptr;
_groups_required = 0;
}
_interface.mixerChanged();
}
int MixingOutput::loadMixer(const char *buf, unsigned len)
{
if (_mixers == nullptr) {
_mixers = new MixerGroup();
}
if (_mixers == nullptr) {
_groups_required = 0;
return -ENOMEM;
}
int ret = _mixers->load_from_buf(controlCallback, (uintptr_t)this, buf, len);
if (ret != 0) {
PX4_ERR("mixer load failed with %d", ret);
delete _mixers;
_mixers = nullptr;
_groups_required = 0;
return ret;
}
_mixers->groups_required(_groups_required);
PX4_DEBUG("loaded mixers \n%s\n", buf);
updateParams();
_interface.mixerChanged();
return ret;
}

View File

@ -165,17 +165,6 @@ public:
void setMaxTopicUpdateRate(unsigned max_topic_update_interval_us);
/**
* Reset (unload) the complete mixer.
*/
void resetMixer();
/**
* Load (append) a new mixer from a buffer.
* @return 0 on success, <0 error otherwise
*/
int loadMixer(const char *buf, unsigned len);
const actuator_armed_s &armed() const { return _armed; }
bool initialized() const { return _use_dynamic_mixing || _mixers != nullptr; }

View File

@ -234,17 +234,6 @@ PWMSim::ioctl(device::file_t *filp, int cmd, unsigned long arg)
*(unsigned *)arg = OutputModuleInterface::MAX_ACTUATORS;
break;
case MIXERIOCRESET:
_mixing_output.resetMixer();
break;
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
unsigned buflen = strlen(buf);
ret = _mixing_output.loadMixer(buf, buflen);
break;
}
default:
ret = -ENOTTY;
break;

View File

@ -35,7 +35,6 @@
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_pwm_output.h>
#include <lib/mixer_module/mixer_module.hpp>
#include <px4_platform_common/px4_config.h>