mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
more px4fmu-v1 cleanup (#7981)
This commit is contained in:
parent
0780e430fd
commit
4e6ca271e7
@ -54,6 +54,4 @@ then
|
||||
param set ATT_BIAS_MAX 0.0
|
||||
|
||||
param set CBRK_IO_SAFETY 22027
|
||||
fi
|
||||
|
||||
set HIL no
|
||||
fi
|
||||
@ -1,47 +0,0 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name AR.Drone Frame
|
||||
#
|
||||
# @type Quadrotor x
|
||||
# @class Copter
|
||||
#
|
||||
# @board px4fmu-v2 exclude
|
||||
# @board px4fmu-v3 exclude
|
||||
# @board px4fmu-v4 exclude
|
||||
# @board px4fmu-v4pro exclude
|
||||
# @board px4fmu-v5 exclude
|
||||
# @board aerofc-v1 exclude
|
||||
#
|
||||
# @maintainer Lorenz Meier <lorenz@px4.io>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.mc_defaults
|
||||
|
||||
#
|
||||
# Load default params for this platform
|
||||
#
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
param set MC_ROLL_P 6.0
|
||||
param set MC_ROLLRATE_P 0.14
|
||||
param set MC_ROLLRATE_I 0.1
|
||||
param set MC_ROLLRATE_D 0.002
|
||||
param set MC_PITCH_P 6.0
|
||||
param set MC_PITCHRATE_P 0.14
|
||||
param set MC_PITCHRATE_I 0.1
|
||||
param set MC_PITCHRATE_D 0.002
|
||||
param set MC_YAW_P 2.0
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.2
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.8
|
||||
|
||||
param set BAT_V_DIV 34.32838
|
||||
fi
|
||||
|
||||
set OUTPUT_MODE ardrone
|
||||
set USE_IO no
|
||||
set MIXER skip
|
||||
# set MAV_TYPE because no specific mixer is set
|
||||
set MAV_TYPE 2
|
||||
@ -120,9 +120,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
# This is a FMUv2+ thing
|
||||
|
||||
#MindPX has not aux mixer
|
||||
if ver hwcmp MINDPX_V2
|
||||
then
|
||||
set MIXER_AUX none
|
||||
@ -138,6 +135,11 @@ then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V5
|
||||
then
|
||||
set MIXER_AUX none
|
||||
@ -168,7 +170,7 @@ then
|
||||
if fmu mode_${AUX_MODE} $FMU_ARGS
|
||||
then
|
||||
# Append aux mixer to main device
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
if param compare SYS_HITL 1
|
||||
then
|
||||
if mixer append ${OUTPUT_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
|
||||
@ -41,9 +41,7 @@ mount -t procfs /proc
|
||||
#
|
||||
# Start CDC/ACM serial driver
|
||||
#
|
||||
if sercon
|
||||
then
|
||||
fi
|
||||
sercon
|
||||
|
||||
#
|
||||
# Default to auto-start mode.
|
||||
@ -68,10 +66,10 @@ then
|
||||
hardfault_log reset
|
||||
tone_alarm stop
|
||||
fi
|
||||
else
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
fi
|
||||
else
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
fi
|
||||
else
|
||||
tone_alarm MBAGP
|
||||
if mkfatfs /dev/mmcsd0
|
||||
@ -141,14 +139,8 @@ then
|
||||
fi
|
||||
|
||||
# FMUv5 may have both PWM I2C RGB LED support
|
||||
|
||||
rgbled_pwm start
|
||||
|
||||
# Currently unused, but might be useful down the road
|
||||
#if pca8574 start
|
||||
#then
|
||||
#fi
|
||||
|
||||
#
|
||||
# Set AUTOCNF flag to use it in AUTOSTART scripts
|
||||
#
|
||||
@ -174,7 +166,6 @@ then
|
||||
#
|
||||
# Set default values
|
||||
#
|
||||
set HIL no
|
||||
set VEHICLE_TYPE none
|
||||
set MIXER none
|
||||
set MIXER_AUX none
|
||||
@ -197,66 +188,37 @@ then
|
||||
set FMU_ARGS ""
|
||||
set MAVLINK_F default
|
||||
set MAVLINK_COMPANION_DEVICE /dev/ttyS2
|
||||
set EXIT_ON_END no
|
||||
set MAV_TYPE none
|
||||
set FAILSAFE none
|
||||
set USE_IO yes
|
||||
set USE_IO no
|
||||
set LOGGER_BUF 16
|
||||
|
||||
if param compare SYS_FMU_TASK 1
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
set FMU_ARGS "-t"
|
||||
param set SYS_FMU_TASK 1
|
||||
fi
|
||||
|
||||
if param compare SYS_HITL 1
|
||||
if ver hwcmp PX4FMU_V4PRO
|
||||
then
|
||||
# Enable HITL mode
|
||||
set HIL yes
|
||||
param set SYS_FMU_TASK 1
|
||||
fi
|
||||
|
||||
#
|
||||
# Set USE_IO flag
|
||||
#
|
||||
if param compare SYS_USE_IO 1
|
||||
if ver hwcmp PX4FMU_V5
|
||||
then
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
set USE_IO no
|
||||
fi
|
||||
param set SYS_FMU_TASK 1
|
||||
set MAVLINK_COMPANION_DEVICE /dev/ttyS3
|
||||
|
||||
if ver hwcmp PX4FMU_V5
|
||||
then
|
||||
set USE_IO no
|
||||
set MAVLINK_COMPANION_DEVICE /dev/ttyS3
|
||||
fi
|
||||
set LOGGER_BUF 64
|
||||
param set SDLOG_MODE 2
|
||||
fi
|
||||
|
||||
if ver hwcmp MINDPX_V2
|
||||
if ver hwcmp CRAZYFLIE
|
||||
then
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
set USE_IO no
|
||||
param set SYS_AUTOSTART 4900
|
||||
set AUTOCNF yes
|
||||
fi
|
||||
|
||||
if ver hwcmp CRAZYFLIE
|
||||
then
|
||||
set USE_IO no
|
||||
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
param set SYS_AUTOSTART 4900
|
||||
set AUTOCNF yes
|
||||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
set USE_IO no
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROCORE2
|
||||
then
|
||||
set USE_IO no
|
||||
fi
|
||||
else
|
||||
set USE_IO no
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
@ -271,12 +233,24 @@ then
|
||||
param set SYS_AUTOSTART 4070
|
||||
fi
|
||||
|
||||
#
|
||||
# Set USE_IO flag
|
||||
#
|
||||
if param compare SYS_USE_IO 1
|
||||
then
|
||||
set USE_IO yes
|
||||
fi
|
||||
|
||||
if param compare SYS_FMU_TASK 1
|
||||
then
|
||||
set FMU_ARGS "-t"
|
||||
fi
|
||||
|
||||
#
|
||||
# Set parameters and env variables for selected AUTOSTART
|
||||
#
|
||||
if param compare SYS_AUTOSTART 0
|
||||
then
|
||||
ekf2 start
|
||||
else
|
||||
sh /etc/init.d/rc.autostart
|
||||
fi
|
||||
@ -295,25 +269,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Wipe incompatible settings for boards not having two outputs
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
set MIXER_AUX none
|
||||
param set SYS_FMU_TASK 1
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V5
|
||||
then
|
||||
set MIXER_AUX none
|
||||
param set SYS_FMU_TASK 1
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
||||
#
|
||||
# Override parameters from user configuration file
|
||||
#
|
||||
@ -415,12 +370,6 @@ then
|
||||
then
|
||||
# Need IO for output but it not present, disable output
|
||||
set OUTPUT_MODE none
|
||||
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == ardrone ]
|
||||
then
|
||||
set FMU_MODE gpio_serial
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == tap_esc ]
|
||||
@ -428,13 +377,6 @@ then
|
||||
set FMU_MODE rcin
|
||||
fi
|
||||
|
||||
if [ $HIL == yes ]
|
||||
then
|
||||
set OUTPUT_MODE hil
|
||||
else
|
||||
gps start
|
||||
fi
|
||||
|
||||
set DATAMAN_OPT ""
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
@ -453,37 +395,21 @@ then
|
||||
|
||||
#
|
||||
# Sensors System (start before Commander so Preflight checks are properly run)
|
||||
#
|
||||
if [ $HIL == yes ]
|
||||
# commander Needs to be this early for in-air-restarts
|
||||
if param compare SYS_HITL 1
|
||||
then
|
||||
set OUTPUT_MODE hil
|
||||
sensors start -h
|
||||
commander start --hil
|
||||
else
|
||||
gps start
|
||||
sh /etc/init.d/rc.sensors
|
||||
fi
|
||||
unset HIL
|
||||
|
||||
# Needs to be this early for in-air-restarts
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
then
|
||||
commander start --hil
|
||||
else
|
||||
commander start
|
||||
commander start
|
||||
fi
|
||||
|
||||
if send_event start
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Start CPU load monitor
|
||||
#
|
||||
send_event start
|
||||
load_mon start
|
||||
|
||||
#
|
||||
# Start primary output
|
||||
#
|
||||
set TTYS1_BUSY no
|
||||
|
||||
#
|
||||
# Check if UAVCAN is enabled, default to it for ESCs
|
||||
#
|
||||
@ -540,7 +466,7 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
||||
if [ $OUTPUT_MODE == fmu ]
|
||||
then
|
||||
if fmu mode_$FMU_MODE $FMU_ARGS
|
||||
then
|
||||
@ -597,7 +523,7 @@ then
|
||||
fi
|
||||
fi
|
||||
else
|
||||
if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ]
|
||||
if [ $OUTPUT_MODE != fmu ]
|
||||
then
|
||||
if fmu mode_${FMU_MODE} $FMU_ARGS
|
||||
then
|
||||
@ -612,27 +538,19 @@ then
|
||||
if [ $MAVLINK_F == default ]
|
||||
then
|
||||
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
set MAVLINK_F "-r 1200 -f"
|
||||
|
||||
# Avoid using ttyS1 for MAVLink on FMUv4
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS0"
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS1"
|
||||
# Start MAVLink on Wifi (ESP8266 port)
|
||||
mavlink start -r 20000 -m config -b 921600 -d /dev/ttyS0
|
||||
fi
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
set MAVLINK_F "-r 1200 -f"
|
||||
# Avoid using ttyS1 for MAVLink on FMUv4
|
||||
if ver hwcmp PX4FMU_V4
|
||||
then
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS1"
|
||||
# Start MAVLink on Wifi (ESP8266 port)
|
||||
mavlink start -r 20000 -m config -b 921600 -d /dev/ttyS0
|
||||
fi
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS3"
|
||||
fi
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
set MAVLINK_F "-r 1200 -d /dev/ttyS3"
|
||||
fi
|
||||
|
||||
if ver hwcmp CRAZYFLIE
|
||||
@ -764,6 +682,7 @@ then
|
||||
|
||||
if ver hwcmp AEROFC_V1
|
||||
then
|
||||
# don't start mavlink ttyACM0 on aerofc_v1
|
||||
else
|
||||
# Start MAVLink
|
||||
mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
|
||||
@ -777,14 +696,6 @@ then
|
||||
sdlog2 start -r 100 -a -b 9 -t
|
||||
else
|
||||
set LOGGER_ARGS ""
|
||||
#
|
||||
# Adjust FMUv5 logging settings
|
||||
#
|
||||
if ver hwcmp PX4FMU_V5
|
||||
then
|
||||
set LOGGER_BUF 64
|
||||
param set SDLOG_MODE 2
|
||||
fi
|
||||
|
||||
if param compare SDLOG_MODE 1
|
||||
then
|
||||
@ -1024,6 +935,7 @@ then
|
||||
if [ $VEHICLE_TYPE == none ]
|
||||
then
|
||||
echo "No autostart ID found"
|
||||
ekf2 start
|
||||
fi
|
||||
|
||||
# Start any custom addons
|
||||
@ -1100,10 +1012,3 @@ unset TUNE_ERR
|
||||
|
||||
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
|
||||
mavlink boot_complete
|
||||
|
||||
if [ $EXIT_ON_END == yes ]
|
||||
then
|
||||
echo "NSH exit"
|
||||
exit
|
||||
fi
|
||||
unset EXIT_ON_END
|
||||
|
||||
@ -39,7 +39,6 @@ px4_add_module(
|
||||
px4io.cpp
|
||||
px4io_uploader.cpp
|
||||
px4io_serial.cpp
|
||||
px4io_i2c.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
||||
@ -3066,14 +3066,6 @@ get_interface()
|
||||
goto got;
|
||||
}
|
||||
|
||||
#ifdef PX4_I2C_OBDEV_PX4IO
|
||||
interface = PX4IO_i2c_interface();
|
||||
#endif
|
||||
|
||||
if (interface != nullptr) {
|
||||
goto got;
|
||||
}
|
||||
|
||||
errx(1, "cannot alloc interface");
|
||||
|
||||
got:
|
||||
|
||||
@ -41,10 +41,6 @@
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#ifdef PX4_I2C_OBDEV_PX4IO
|
||||
device::Device *PX4IO_i2c_interface();
|
||||
#endif
|
||||
|
||||
#ifdef PX4IO_SERIAL_BASE
|
||||
device::Device *PX4IO_serial_interface();
|
||||
#endif
|
||||
|
||||
@ -1,177 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 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 px4io_i2c.cpp
|
||||
*
|
||||
* I2C interface for PX4IO
|
||||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include "px4io_driver.h"
|
||||
|
||||
#ifdef PX4_I2C_OBDEV_PX4IO
|
||||
|
||||
class PX4IO_I2C : public device::I2C
|
||||
{
|
||||
public:
|
||||
PX4IO_I2C(int bus, uint8_t address);
|
||||
virtual ~PX4IO_I2C();
|
||||
|
||||
virtual int init();
|
||||
virtual int read(unsigned offset, void *data, unsigned count = 1);
|
||||
virtual int write(unsigned address, void *data, unsigned count = 1);
|
||||
virtual int ioctl(unsigned operation, unsigned &arg);
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
device::Device
|
||||
*PX4IO_i2c_interface()
|
||||
{
|
||||
return new PX4IO_I2C(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO);
|
||||
}
|
||||
|
||||
PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
|
||||
I2C("PX4IO_i2c", nullptr, bus, address, 400000)
|
||||
{
|
||||
_retries = 3;
|
||||
}
|
||||
|
||||
PX4IO_I2C::~PX4IO_I2C()
|
||||
{
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_I2C::init()
|
||||
{
|
||||
int ret;
|
||||
|
||||
ret = I2C::init();
|
||||
|
||||
if (ret != OK) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* XXX really should do something more here */
|
||||
|
||||
out:
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_I2C::ioctl(unsigned operation, unsigned &arg)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_I2C::write(unsigned address, void *data, unsigned count)
|
||||
{
|
||||
uint8_t page = address >> 8;
|
||||
uint8_t offset = address & 0xff;
|
||||
const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
|
||||
|
||||
/* set up the transfer */
|
||||
uint8_t addr[2] = {
|
||||
page,
|
||||
offset
|
||||
};
|
||||
|
||||
i2c_msg_s msgv[2];
|
||||
|
||||
msgv[0].flags = 0;
|
||||
msgv[0].buffer = addr;
|
||||
msgv[0].length = 2;
|
||||
|
||||
msgv[1].flags = I2C_M_NORESTART;
|
||||
msgv[1].buffer = (uint8_t *)values;
|
||||
msgv[1].length = 2 * count;
|
||||
|
||||
int ret = transfer(msgv, 2);
|
||||
|
||||
if (ret == OK) {
|
||||
ret = count;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_I2C::read(unsigned address, void *data, unsigned count)
|
||||
{
|
||||
uint8_t page = address >> 8;
|
||||
uint8_t offset = address & 0xff;
|
||||
const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
|
||||
|
||||
/* set up the transfer */
|
||||
uint8_t addr[2] = {
|
||||
page,
|
||||
offset
|
||||
};
|
||||
i2c_msg_s msgv[2];
|
||||
|
||||
msgv[0].flags = 0;
|
||||
msgv[0].buffer = addr;
|
||||
msgv[0].length = 2;
|
||||
|
||||
msgv[1].flags = I2C_M_READ;
|
||||
msgv[1].buffer = (uint8_t *)values;
|
||||
msgv[1].length = 2 * count;
|
||||
|
||||
int ret = transfer(msgv, 2);
|
||||
|
||||
if (ret == OK) {
|
||||
ret = count;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* PX4_I2C_OBDEV_PX4IO */
|
||||
@ -42,6 +42,19 @@
|
||||
#include <px4_config.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* Set usage of IO board
|
||||
*
|
||||
* Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up.
|
||||
*
|
||||
* @boolean
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @reboot_required true
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_USE_IO, 1);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 1
|
||||
*
|
||||
@ -235,3 +248,61 @@ PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM8, 0);
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0);
|
||||
|
||||
/**
|
||||
* PWM input channel that provides RSSI.
|
||||
*
|
||||
* 0: do not read RSSI from input channel
|
||||
* 1-18: read RSSI from specified input channel
|
||||
*
|
||||
* Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @value 0 Unassigned
|
||||
* @value 1 Channel 1
|
||||
* @value 2 Channel 2
|
||||
* @value 3 Channel 3
|
||||
* @value 4 Channel 4
|
||||
* @value 5 Channel 5
|
||||
* @value 6 Channel 6
|
||||
* @value 7 Channel 7
|
||||
* @value 8 Channel 8
|
||||
* @value 9 Channel 9
|
||||
* @value 10 Channel 10
|
||||
* @value 11 Channel 11
|
||||
* @value 12 Channel 12
|
||||
* @value 13 Channel 13
|
||||
* @value 14 Channel 14
|
||||
* @value 15 Channel 15
|
||||
* @value 16 Channel 16
|
||||
* @value 17 Channel 17
|
||||
* @value 18 Channel 18
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_CHAN, 0);
|
||||
|
||||
/**
|
||||
* Max input value for RSSI reading.
|
||||
*
|
||||
* Only used if RC_RSSI_PWM_CHAN > 0
|
||||
*
|
||||
* @min 0
|
||||
* @max 2000
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MAX, 1000);
|
||||
|
||||
/**
|
||||
* Min input value for RSSI reading.
|
||||
*
|
||||
* Only used if RC_RSSI_PWM_CHAN > 0
|
||||
*
|
||||
* @min 0
|
||||
* @max 2000
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
|
||||
|
||||
@ -2089,7 +2089,6 @@ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
|
||||
|
||||
|
||||
/**
|
||||
* Threshold for selecting offboard mode
|
||||
*
|
||||
@ -2108,7 +2107,6 @@ PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_OFFB_TH, 0.5f);
|
||||
|
||||
|
||||
/**
|
||||
* Threshold for the kill switch
|
||||
*
|
||||
@ -2217,64 +2215,6 @@ PARAM_DEFINE_FLOAT(RC_STAB_TH, 0.5f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_MAN_TH, 0.5f);
|
||||
|
||||
/**
|
||||
* PWM input channel that provides RSSI.
|
||||
*
|
||||
* 0: do not read RSSI from input channel
|
||||
* 1-18: read RSSI from specified input channel
|
||||
*
|
||||
* Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @value 0 Unassigned
|
||||
* @value 1 Channel 1
|
||||
* @value 2 Channel 2
|
||||
* @value 3 Channel 3
|
||||
* @value 4 Channel 4
|
||||
* @value 5 Channel 5
|
||||
* @value 6 Channel 6
|
||||
* @value 7 Channel 7
|
||||
* @value 8 Channel 8
|
||||
* @value 9 Channel 9
|
||||
* @value 10 Channel 10
|
||||
* @value 11 Channel 11
|
||||
* @value 12 Channel 12
|
||||
* @value 13 Channel 13
|
||||
* @value 14 Channel 14
|
||||
* @value 15 Channel 15
|
||||
* @value 16 Channel 16
|
||||
* @value 17 Channel 17
|
||||
* @value 18 Channel 18
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_CHAN, 0);
|
||||
|
||||
/**
|
||||
* Max input value for RSSI reading.
|
||||
*
|
||||
* Only used if RC_RSSI_PWM_CHAN > 0
|
||||
*
|
||||
* @min 0
|
||||
* @max 2000
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MAX, 1000);
|
||||
|
||||
/**
|
||||
* Min input value for RSSI reading.
|
||||
*
|
||||
* Only used if RC_RSSI_PWM_CHAN > 0
|
||||
*
|
||||
* @min 0
|
||||
* @max 2000
|
||||
* @group Radio Calibration
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
|
||||
|
||||
/**
|
||||
* Sample rate of the remote control values for the low pass filter on roll,pitch, yaw and throttle
|
||||
*
|
||||
|
||||
@ -1,42 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 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.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE systemcmds__i2c
|
||||
MAIN i2c
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
i2c.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
@ -1,146 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 i2c.c
|
||||
*
|
||||
* i2c hacking tool
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/mount.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include "systemlib/systemlib.h"
|
||||
|
||||
#ifndef PX4_I2C_BUS_ONBOARD
|
||||
# error PX4_I2C_BUS_ONBOARD not defined, no device interface
|
||||
#endif
|
||||
#ifndef PX4_I2C_OBDEV_PX4IO
|
||||
# error PX4_I2C_OBDEV_PX4IO not defined
|
||||
#endif
|
||||
|
||||
__EXPORT int i2c_main(int argc, char *argv[]);
|
||||
|
||||
static int transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len);
|
||||
|
||||
static struct i2c_master_s *i2c;
|
||||
|
||||
int i2c_main(int argc, char *argv[])
|
||||
{
|
||||
/* find the right I2C */
|
||||
i2c = px4_i2cbus_initialize(PX4_I2C_BUS_ONBOARD);
|
||||
|
||||
if (i2c == NULL) {
|
||||
PX4_ERR("failed to locate I2C bus");
|
||||
return 1;
|
||||
}
|
||||
|
||||
usleep(100000);
|
||||
|
||||
uint8_t buf[] = { 0, 4};
|
||||
int ret = transfer(PX4_I2C_OBDEV_PX4IO, buf, sizeof(buf), NULL, 0);
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("send failed - %d", ret);
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint32_t val;
|
||||
ret = transfer(PX4_I2C_OBDEV_PX4IO, NULL, 0, (uint8_t *)&val, sizeof(val));
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("recive failed - %d", ret);
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO("got 0x%08x", val);
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
|
||||
{
|
||||
struct i2c_msg_s msgv[2];
|
||||
unsigned msgs;
|
||||
int ret;
|
||||
|
||||
// debug("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
|
||||
|
||||
msgs = 0;
|
||||
|
||||
if (send_len > 0) {
|
||||
msgv[msgs].frequency = 400000;
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = 0;
|
||||
msgv[msgs].buffer = send;
|
||||
msgv[msgs].length = send_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
msgv[msgs].frequency = 400000;
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = I2C_M_READ;
|
||||
msgv[msgs].buffer = recv;
|
||||
msgv[msgs].length = recv_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (msgs == 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
ret = I2C_TRANSFER(i2c, &msgv[0], msgs);
|
||||
|
||||
// reset the I2C bus to unwedge on error
|
||||
if (ret != OK) {
|
||||
up_i2creset(i2c);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user