Browse Source
Using mixers on the IO side had a remote benefit of being able to override all control surfaces with a radio remote on a fixed wing. This ended up not being used that much and since the original design 10 years ago (2011) we have been able to convince ourselves that the overall system stability is at a level where this marginal benefit, which is not present on multicopters, is not worth the hazzle. Co-authored-by: Beat Küng <beat-kueng@gmx.net> Co-authored-by: Daniel Agar <daniel@agar.ca>master
Daniel Agar
4 years ago
59 changed files with 1119 additions and 4139 deletions
@ -1,23 +0,0 @@
@@ -1,23 +0,0 @@
|
||||
#!/bin/sh |
||||
# |
||||
# PX4IO interface init script. |
||||
# |
||||
|
||||
# If $OUTPUT_MODE indicated Hardware-int-the-loop simulation, px4io should not publish actuator_outputs, |
||||
# instead, pwm_out_sim will publish that uORB |
||||
if [ $OUTPUT_MODE = hil ] |
||||
then |
||||
set HIL_ARG $OUTPUT_MODE |
||||
fi |
||||
|
||||
if [ $IO_PRESENT = yes ] |
||||
then |
||||
if px4io start $HIL_ARG |
||||
then |
||||
# Allow PX4IO to recover from midair restarts. |
||||
px4io recovery |
||||
else |
||||
echo "PX4IO start failed" |
||||
tune_control play -t 18 # PROG_PX4IO_ERR |
||||
fi |
||||
fi |
@ -1,80 +0,0 @@
@@ -1,80 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-2014 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_rc_input.h |
||||
* |
||||
* R/C input interface. |
||||
*/ |
||||
|
||||
#ifndef _DRV_RC_INPUT_H |
||||
#define _DRV_RC_INPUT_H |
||||
|
||||
#include <stdint.h> |
||||
#include <sys/ioctl.h> |
||||
#include <uORB/topics/input_rc.h> |
||||
|
||||
#include "drv_orb_dev.h" |
||||
|
||||
/**
|
||||
* Path for the default R/C input device. |
||||
* |
||||
* Note that on systems with more than one R/C input path (e.g. |
||||
* PX4FMU with PX4IO connected) there may be other devices that |
||||
* respond to this protocol. |
||||
* |
||||
* Input data may be obtained by subscribing to the input_rc |
||||
* object, or by poll/reading from the device. |
||||
*/ |
||||
#define RC_INPUT0_DEVICE_PATH "/dev/input_rc0" |
||||
|
||||
/**
|
||||
* Maximum RSSI value |
||||
*/ |
||||
#define RC_INPUT_RSSI_MAX 100 |
||||
|
||||
/**
|
||||
* Input signal type, value is a control position from zero to 100 |
||||
* percent. |
||||
*/ |
||||
typedef uint16_t rc_input_t; |
||||
|
||||
#define _RC_INPUT_BASE 0x2b00 |
||||
|
||||
/** Enable RSSI input via ADC */ |
||||
#define RC_INPUT_ENABLE_RSSI_ANALOG _IOC(_RC_INPUT_BASE, 1) |
||||
|
||||
/** Enable RSSI input via PWM signal */ |
||||
#define RC_INPUT_ENABLE_RSSI_PWM _IOC(_RC_INPUT_BASE, 2) |
||||
|
||||
#endif /* _DRV_RC_INPUT_H */ |
@ -1,42 +0,0 @@
@@ -1,42 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2017-2018 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 mixer.h |
||||
* |
||||
* PX4IO mixer definitions |
||||
* |
||||
* @author Lorenz Meier <lorenz@px4.io> |
||||
*/ |
||||
#pragma once |
||||
#define PX4IO_MAX_MIXER_LENGTH 330 |
@ -1,74 +0,0 @@
@@ -1,74 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2019 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 test_conv.cpp |
||||
* Tests conversions used across the system. |
||||
*/ |
||||
|
||||
#include <sys/types.h> |
||||
|
||||
#include <stdio.h> |
||||
#include <poll.h> |
||||
#include <stdlib.h> |
||||
#include <unistd.h> |
||||
#include <fcntl.h> |
||||
#include <errno.h> |
||||
|
||||
#include "tests_main.h" |
||||
|
||||
#include <math.h> |
||||
#include <float.h> |
||||
|
||||
#include <unit_test.h> |
||||
#include <px4iofirmware/protocol.h> |
||||
|
||||
int test_conv(int argc, char *argv[]) |
||||
{ |
||||
//PX4_INFO("Testing system conversions");
|
||||
|
||||
for (int i = -10000; i <= 10000; i += 1) { |
||||
float f = i / 10000.0f; |
||||
float fres = REG_TO_FLOAT(FLOAT_TO_REG(f)); |
||||
|
||||
if (fabsf(f - fres) > 0.0001f) { |
||||
PX4_ERR("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", (double)f, REG_TO_SIGNED(FLOAT_TO_REG(f)), |
||||
(double)fres); |
||||
return 1; |
||||
} |
||||
} |
||||
|
||||
//PX4_INFO("All conversions clean");
|
||||
|
||||
return 0; |
||||
} |
Loading…
Reference in new issue