mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 22:32:11 +08:00
pwm_out, dshot: remove mode_* handling and capture ioctl's
They now use all unused pins, whereas camera_capture, camera_trigger and pwm_input modules start before to reserve their pins.
This commit is contained in:
@@ -21,8 +21,6 @@ then
|
||||
fi
|
||||
|
||||
# initialize script variables
|
||||
set AUX_MODE none
|
||||
set AUX_BANK2 none
|
||||
set IO_PRESENT no
|
||||
set MAV_TYPE none
|
||||
set MIXER none
|
||||
|
||||
@@ -29,12 +29,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
# USE_IO is set to 'no' for all boards w/o px4io driver or SYS_USE_IO disabled
|
||||
if [ $USE_IO = no -a $AUX_BANK2 = none ]
|
||||
then
|
||||
set AUX_MODE none
|
||||
fi
|
||||
|
||||
#
|
||||
# Set the default output mode if none was set.
|
||||
#
|
||||
@@ -76,15 +70,6 @@ then
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE = $OUTPUT_CMD ]
|
||||
then
|
||||
if ! $OUTPUT_CMD mode_$FMU_MODE
|
||||
then
|
||||
echo "$OUTPUT_CMD start failed"
|
||||
tune_control play error
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE = uavcan_esc ]
|
||||
then
|
||||
if param compare UAVCAN_ENABLE 0
|
||||
@@ -98,6 +83,15 @@ then
|
||||
. ${R}etc/init.d/rc.io
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE = $OUTPUT_CMD -o $OUTPUT_MODE = io ]
|
||||
then
|
||||
if ! $OUTPUT_CMD start
|
||||
then
|
||||
echo "$OUTPUT_CMD start failed"
|
||||
tune_control play error
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start IO for RC input if needed.
|
||||
#
|
||||
@@ -161,7 +155,7 @@ else
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $MIXER_AUX != none -a $AUX_MODE != none ]
|
||||
if [ $MIXER_AUX != none ]
|
||||
then
|
||||
#
|
||||
# Load aux mixer.
|
||||
@@ -179,34 +173,26 @@ then
|
||||
|
||||
if [ $MIXER_AUX_FILE != none ]
|
||||
then
|
||||
# Start the output module
|
||||
if $OUTPUT_CMD mode_${AUX_MODE}
|
||||
# Append aux mixer to main device.
|
||||
if param greater SYS_HITL 0
|
||||
then
|
||||
# Append aux mixer to main device.
|
||||
if param greater SYS_HITL 0
|
||||
if mixer append ${OUTPUT_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
if mixer append ${OUTPUT_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} appended to ${OUTPUT_DEV}"
|
||||
else
|
||||
echo "ERROR [init] Failed appending mixer: ${MIXER_AUX_FILE}"
|
||||
fi
|
||||
fi
|
||||
if [ -e $OUTPUT_AUX_DEV -a $OUTPUT_MODE != hil ]
|
||||
then
|
||||
if mixer load ${OUTPUT_AUX_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} on ${OUTPUT_AUX_DEV}"
|
||||
else
|
||||
echo "ERROR [init] Failed loading mixer: ${MIXER_AUX_FILE}"
|
||||
fi
|
||||
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} appended to ${OUTPUT_DEV}"
|
||||
else
|
||||
echo "INFO [init] setting PWM_AUX_OUT none"
|
||||
set PWM_AUX_OUT none
|
||||
echo "ERROR [init] Failed appending mixer: ${MIXER_AUX_FILE}"
|
||||
fi
|
||||
fi
|
||||
if [ -e $OUTPUT_AUX_DEV -a $OUTPUT_MODE != hil ]
|
||||
then
|
||||
if mixer load ${OUTPUT_AUX_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} on ${OUTPUT_AUX_DEV}"
|
||||
else
|
||||
echo "ERROR [init] Failed loading mixer: ${MIXER_AUX_FILE}"
|
||||
fi
|
||||
else
|
||||
echo "ERROR: Could not start: pwm_out mode_pwm"
|
||||
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
|
||||
echo "INFO [init] setting PWM_AUX_OUT none"
|
||||
set PWM_AUX_OUT none
|
||||
fi
|
||||
|
||||
@@ -228,36 +214,6 @@ fi
|
||||
|
||||
param set PWM_AUX_OUT ${PWM_AUX_OUT}
|
||||
|
||||
if [ $MIXER_AUX != none -a $AUX_MODE = none -a -e $OUTPUT_AUX_DEV ]
|
||||
then
|
||||
#
|
||||
# Load aux mixer.
|
||||
#
|
||||
if [ -f ${SDCARD_MIXERS_PATH}/${MIXER_AUX}.aux.mix ]
|
||||
then
|
||||
set MIXER_AUX_FILE ${SDCARD_MIXERS_PATH}/${MIXER_AUX}.aux.mix
|
||||
else
|
||||
|
||||
if [ -f /etc/mixers/${MIXER_AUX}.aux.mix ]
|
||||
then
|
||||
set MIXER_AUX_FILE /etc/mixers/${MIXER_AUX}.aux.mix
|
||||
fi
|
||||
fi
|
||||
|
||||
if mixer load ${OUTPUT_AUX_DEV} ${MIXER_AUX_FILE}
|
||||
then
|
||||
echo "INFO [init] Mixer: ${MIXER_AUX_FILE} on ${OUTPUT_AUX_DEV}"
|
||||
|
||||
# Set PWM_AUX output frequency.
|
||||
if [ $PWM_AUX_RATE != none ]
|
||||
then
|
||||
pwm rate -c ${PWM_AUX_OUT} -r ${PWM_AUX_RATE} -d ${OUTPUT_AUX_DEV}
|
||||
fi
|
||||
else
|
||||
echo "ERROR [init] Failed loading mixer: ${MIXER_AUX_FILE}"
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $OUTPUT_MODE = pwm_out -o $OUTPUT_MODE = io ]
|
||||
then
|
||||
if [ $PWM_OUT != none ]
|
||||
|
||||
@@ -22,10 +22,8 @@ set +e
|
||||
#
|
||||
set R /
|
||||
set AUTOCNF no
|
||||
set AUX_MODE pwm
|
||||
set FCONFIG /fs/microsd/etc/config.txt
|
||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||
set FMU_MODE pwm
|
||||
set FRC /fs/microsd/etc/rc.txt
|
||||
set IOFW "/etc/extras/px4_io-v2_default.bin"
|
||||
set IO_PRESENT no
|
||||
@@ -376,52 +374,9 @@ else
|
||||
commander start
|
||||
fi
|
||||
|
||||
# Sensors on the PWM interface bank.
|
||||
if param compare -s SENS_EN_LL40LS 1
|
||||
then
|
||||
# Clear pins 5 and 6.
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
fi
|
||||
|
||||
|
||||
# Check if ATS is enabled
|
||||
if param compare FD_EXT_ATS_EN 1
|
||||
then
|
||||
# Clear pins 5 and 6.
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
fi
|
||||
|
||||
if param greater -s TRIG_MODE 0
|
||||
then
|
||||
if param compare TRIG_PINS_EX 0
|
||||
then
|
||||
# We ONLY support trigger on pins 5+6 or 7+8 when simultanously using AUX for actuator output.
|
||||
if param compare TRIG_PINS 56
|
||||
then
|
||||
# clear pins 5 and 6
|
||||
set FMU_MODE pwm4
|
||||
set AUX_MODE pwm4
|
||||
else
|
||||
if param compare TRIG_PINS 78
|
||||
then
|
||||
# clear pins 7 and 8
|
||||
set FMU_MODE pwm6
|
||||
set AUX_MODE pwm6
|
||||
else
|
||||
set FMU_MODE none
|
||||
set AUX_MODE none
|
||||
fi
|
||||
fi
|
||||
else
|
||||
if param compare TRIG_PINS_EX 12288
|
||||
then
|
||||
set FMU_MODE pwm12
|
||||
set AUX_MODE pwm12
|
||||
fi
|
||||
fi
|
||||
|
||||
camera_trigger start
|
||||
camera_feedback start
|
||||
fi
|
||||
@@ -449,14 +404,7 @@ else
|
||||
rc_input start $RC_INPUT_ARGS
|
||||
fi
|
||||
|
||||
#
|
||||
# Configure vehicle type specific parameters.
|
||||
# Note: rc.vehicle_setup is the entry point for rc.interface,
|
||||
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
|
||||
#
|
||||
. ${R}etc/init.d/rc.vehicle_setup
|
||||
|
||||
# Camera capture driver
|
||||
# Camera capture driver (before pwm_out)
|
||||
if param greater -s CAM_CAP_FBACK 0
|
||||
then
|
||||
if camera_capture start
|
||||
@@ -465,6 +413,13 @@ else
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Configure vehicle type specific parameters.
|
||||
# Note: rc.vehicle_setup is the entry point for rc.interface,
|
||||
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
|
||||
#
|
||||
. ${R}etc/init.d/rc.vehicle_setup
|
||||
|
||||
#
|
||||
# Start the navigator.
|
||||
#
|
||||
@@ -564,10 +519,8 @@ fi
|
||||
#
|
||||
unset R
|
||||
unset AUTOCNF
|
||||
unset AUX_MODE
|
||||
unset FCONFIG
|
||||
unset FEXTRAS
|
||||
unset FMU_MODE
|
||||
unset FRC
|
||||
unset IO_PRESENT
|
||||
unset IOFW
|
||||
|
||||
@@ -131,15 +131,14 @@ PARAM_DEFINE_INT32(TRIG_MODE, 0);
|
||||
* Camera trigger pin
|
||||
*
|
||||
* Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board,
|
||||
* MAIN1-MAIN8 on controllers without an I/O board. The PWM interface takes two pins per camera, while relay
|
||||
* MAIN1-MAIN8 on controllers without an I/O board).
|
||||
*
|
||||
* The PWM interface takes two pins per camera, while relay
|
||||
* triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6.
|
||||
* For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will
|
||||
* be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61.
|
||||
* In GPIO mode the delay pin to pin is < .2 uS.
|
||||
*
|
||||
* Note: only with a value of 56 or 78 it is possible to use the lower pins for
|
||||
* actuator outputs (e.g. ESC's).
|
||||
*
|
||||
* @min 1
|
||||
* @max 12345678
|
||||
* @decimal 0
|
||||
|
||||
@@ -48,26 +48,10 @@
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/**
|
||||
* Path for the default capture input device.
|
||||
*
|
||||
*
|
||||
*/
|
||||
#define INPUT_CAPTURE_BASE_DEVICE_PATH "/dev/capture"
|
||||
#define INPUT_CAPTURE0_DEVICE_PATH "/dev/capture0"
|
||||
|
||||
typedef void (*capture_callback_t)(void *context, uint32_t chan_index,
|
||||
hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow);
|
||||
|
||||
/**
|
||||
* Maximum number of PWM input channels supported by the device.
|
||||
*/
|
||||
#ifndef INPUT_CAPTURE_MAX_CHANNELS
|
||||
#define INPUT_CAPTURE_MAX_CHANNELS 6
|
||||
#endif
|
||||
|
||||
typedef uint16_t capture_filter_t;
|
||||
typedef uint16_t capture_t;
|
||||
|
||||
typedef enum input_capture_edge {
|
||||
Disabled = 0,
|
||||
@@ -76,12 +60,6 @@ typedef enum input_capture_edge {
|
||||
Both = 3
|
||||
} input_capture_edge;
|
||||
|
||||
typedef struct input_capture_element_t {
|
||||
hrt_abstime time_stamp;
|
||||
input_capture_edge edge;
|
||||
bool overrun;
|
||||
} input_capture_element_t;
|
||||
|
||||
typedef struct input_capture_stats_t {
|
||||
uint32_t edges;
|
||||
uint32_t overflows;
|
||||
@@ -90,90 +68,6 @@ typedef struct input_capture_stats_t {
|
||||
uint16_t latency;
|
||||
} input_capture_stats_t;
|
||||
|
||||
/**
|
||||
* input capture values for a channel
|
||||
*
|
||||
* This allows for Capture input driver values to be set without a
|
||||
* param_get() dependency
|
||||
*/
|
||||
typedef struct input_capture_config_t {
|
||||
uint8_t channel;
|
||||
capture_filter_t filter;
|
||||
input_capture_edge edge;
|
||||
capture_callback_t callback;
|
||||
void *context;
|
||||
|
||||
} input_capture_config_t;
|
||||
|
||||
/*
|
||||
* ioctl() definitions
|
||||
*
|
||||
* Note that ioctls and ORB updates should not be mixed, as the
|
||||
* behaviour of the system in this case is not defined.
|
||||
*/
|
||||
#define _INPUT_CAP_BASE 0x2d00
|
||||
|
||||
/** Set Enable a channel arg is pointer to input_capture_config
|
||||
* with all parameters set.
|
||||
* edge controls the mode: Disable will free the capture channel.
|
||||
* (When edge is Disabled call back and context are ignored)
|
||||
* context may be null. If callback and context are null the
|
||||
* callback will be disabled.
|
||||
* */
|
||||
|
||||
#define INPUT_CAP_SET _PX4_IOC(_INPUT_CAP_BASE, 0)
|
||||
|
||||
/** Set the call back on a capture channel - arg is pointer to
|
||||
* input_capture_config with channel call back and context set
|
||||
* context may be null. If both ate null the call back will be
|
||||
* disabled */
|
||||
#define INPUT_CAP_SET_CALLBACK _PX4_IOC(_INPUT_CAP_BASE, 1)
|
||||
|
||||
/** Get the call back on a capture channel - arg is pointer to
|
||||
* input_capture_config with channel set.
|
||||
*/
|
||||
#define INPUT_CAP_GET_CALLBACK _PX4_IOC(_INPUT_CAP_BASE, 2)
|
||||
|
||||
/** Set Edge a channel arg is pointer to input_capture_config
|
||||
* with channel and edge set */
|
||||
#define INPUT_CAP_SET_EDGE _PX4_IOC(_INPUT_CAP_BASE, 3)
|
||||
|
||||
/** Get Edge for a channel arg is pointer to input_capture_config
|
||||
* with channel set */
|
||||
#define INPUT_CAP_GET_EDGE _PX4_IOC(_INPUT_CAP_BASE, 4)
|
||||
|
||||
/** Set Filter input filter channel arg is pointer to input_capture_config
|
||||
* with channel and filter set */
|
||||
#define INPUT_CAP_SET_FILTER _PX4_IOC(_INPUT_CAP_BASE, 5)
|
||||
|
||||
/** Set Filter input filter channel arg is pointer to input_capture_config
|
||||
* with channel set */
|
||||
#define INPUT_CAP_GET_FILTER _PX4_IOC(_INPUT_CAP_BASE, 6)
|
||||
|
||||
/** Get the number of capture in *(unsigned *)arg */
|
||||
#define INPUT_CAP_GET_COUNT _PX4_IOC(_INPUT_CAP_BASE, 7)
|
||||
|
||||
/** Set the number of capture in (unsigned)arg - allows change of
|
||||
* split between servos and capture */
|
||||
#define INPUT_CAP_SET_COUNT _PX4_IOC(_INPUT_CAP_BASE, 8)
|
||||
|
||||
/** Get channel stats - arg is pointer to input_capture_config
|
||||
* with channel set.
|
||||
*/
|
||||
#define INPUT_CAP_GET_STATS _PX4_IOC(_INPUT_CAP_BASE, 9)
|
||||
|
||||
/** Get channel stats - arg is pointer to input_capture_config
|
||||
* with channel set.
|
||||
*/
|
||||
#define INPUT_CAP_GET_CLR_STATS _PX4_IOC(_INPUT_CAP_BASE, 10)
|
||||
|
||||
/*
|
||||
*
|
||||
*
|
||||
* WARNING WARNING WARNING! DO NOT EXCEED 31 IN IOC INDICES HERE!
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
__EXPORT int up_input_capture_set(unsigned channel, input_capture_edge edge, capture_filter_t filter,
|
||||
capture_callback_t callback, void *context);
|
||||
|
||||
@@ -218,25 +218,7 @@ typedef uint16_t servo_position_t;
|
||||
/** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */
|
||||
#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _PX4_IOC(_PWM_SERVO_BASE, 32)
|
||||
|
||||
/** set auxillary output mode. These correspond to enum Mode in px4fmu/fmu.cpp */
|
||||
#define PWM_SERVO_MODE_NONE 0
|
||||
#define PWM_SERVO_MODE_1PWM 1
|
||||
#define PWM_SERVO_MODE_2PWM 2
|
||||
#define PWM_SERVO_MODE_2PWM2CAP 3
|
||||
#define PWM_SERVO_MODE_3PWM 4
|
||||
#define PWM_SERVO_MODE_3PWM1CAP 5
|
||||
#define PWM_SERVO_MODE_4PWM 6
|
||||
#define PWM_SERVO_MODE_4PWM1CAP 7
|
||||
#define PWM_SERVO_MODE_4PWM2CAP 8
|
||||
#define PWM_SERVO_MODE_5PWM 9
|
||||
#define PWM_SERVO_MODE_5PWM1CAP 10
|
||||
#define PWM_SERVO_MODE_6PWM 11
|
||||
#define PWM_SERVO_MODE_8PWM 12
|
||||
#define PWM_SERVO_MODE_12PWM 13
|
||||
#define PWM_SERVO_MODE_14PWM 14
|
||||
#define PWM_SERVO_MODE_4CAP 15
|
||||
#define PWM_SERVO_MODE_5CAP 16
|
||||
#define PWM_SERVO_MODE_6CAP 17
|
||||
/** set auxillary output mode */
|
||||
#define PWM_SERVO_ENTER_TEST_MODE 18
|
||||
#define PWM_SERVO_EXIT_TEST_MODE 19
|
||||
#define PWM_SERVO_SET_MODE _PX4_IOC(_PWM_SERVO_BASE, 34)
|
||||
|
||||
+12
-837
File diff suppressed because it is too large
Load Diff
@@ -64,64 +64,13 @@ public:
|
||||
DShot();
|
||||
virtual ~DShot();
|
||||
|
||||
enum Mode {
|
||||
MODE_NONE = 0,
|
||||
MODE_1PWM,
|
||||
MODE_2PWM,
|
||||
MODE_2PWM2CAP,
|
||||
MODE_3PWM,
|
||||
MODE_3PWM1CAP,
|
||||
MODE_4PWM,
|
||||
MODE_4PWM1CAP,
|
||||
MODE_4PWM2CAP,
|
||||
MODE_5PWM,
|
||||
MODE_5PWM1CAP,
|
||||
MODE_6PWM,
|
||||
MODE_8PWM,
|
||||
MODE_12PWM,
|
||||
MODE_14PWM,
|
||||
MODE_4CAP,
|
||||
MODE_5CAP,
|
||||
MODE_6CAP,
|
||||
};
|
||||
|
||||
/** Mode given via CLI */
|
||||
enum PortMode {
|
||||
PORT_MODE_UNSET = 0,
|
||||
PORT_FULL_GPIO,
|
||||
PORT_FULL_PWM,
|
||||
PORT_PWM14,
|
||||
PORT_PWM12,
|
||||
PORT_PWM8,
|
||||
PORT_PWM6,
|
||||
PORT_PWM5,
|
||||
PORT_PWM4,
|
||||
PORT_PWM3,
|
||||
PORT_PWM2,
|
||||
PORT_PWM1,
|
||||
PORT_PWM3CAP1,
|
||||
PORT_PWM4CAP1,
|
||||
PORT_PWM4CAP2,
|
||||
PORT_PWM5CAP1,
|
||||
PORT_PWM2CAP2,
|
||||
PORT_CAPTURE,
|
||||
};
|
||||
|
||||
static void capture_trampoline(void *context, const uint32_t channel_index, const hrt_abstime edge_time,
|
||||
const uint32_t edge_state, const uint32_t overflow);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int custom_command(int argc, char *argv[]);
|
||||
|
||||
Mode get_mode() { return _mode; }
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/** change the mode of the running module */
|
||||
static int module_new_mode(const PortMode new_mode);
|
||||
|
||||
void mixerChanged() override;
|
||||
|
||||
/** @see ModuleBase::print_status() */
|
||||
@@ -141,8 +90,6 @@ public:
|
||||
*/
|
||||
int send_command_thread_safe(const dshot_command_t command, const int num_repetitions, const int motor_index);
|
||||
|
||||
int set_mode(const Mode new_mode);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int task_spawn(int argc, char *argv[]);
|
||||
|
||||
@@ -179,19 +126,12 @@ private:
|
||||
int last_motor_index{-1};
|
||||
};
|
||||
|
||||
void capture_callback(const uint32_t channel_index, const hrt_abstime edge_time,
|
||||
const uint32_t edge_state, const uint32_t overflow);
|
||||
|
||||
int capture_ioctl(file *filp, const int cmd, const unsigned long arg);
|
||||
|
||||
void enable_dshot_outputs(const bool enabled);
|
||||
|
||||
void init_telemetry(const char *device);
|
||||
|
||||
void handle_new_telemetry_data(const int motor_index, const DShotTelemetry::EscData &data);
|
||||
|
||||
int pwm_ioctl(file *filp, const int cmd, const unsigned long arg);
|
||||
|
||||
int request_esc_info();
|
||||
|
||||
void Run() override;
|
||||
@@ -215,7 +155,7 @@ private:
|
||||
bool _outputs_on{false};
|
||||
bool _waiting_for_esc_info{false};
|
||||
|
||||
unsigned _num_outputs{0};
|
||||
static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS};
|
||||
uint32_t _output_mask{0};
|
||||
|
||||
int _class_instance{-1};
|
||||
@@ -224,8 +164,6 @@ private:
|
||||
|
||||
Command _current_command{};
|
||||
|
||||
Mode _mode{MODE_NONE};
|
||||
|
||||
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
|
||||
+21
-1043
File diff suppressed because it is too large
Load Diff
@@ -40,7 +40,6 @@
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_input_capture.h>
|
||||
#include <drivers/drv_mixer.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <lib/cdev/CDev.hpp>
|
||||
@@ -64,33 +63,10 @@
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
/** Mode given via CLI */
|
||||
enum PortMode {
|
||||
PORT_MODE_UNSET = 0,
|
||||
PORT_FULL_GPIO,
|
||||
PORT_FULL_PWM,
|
||||
PORT_PWM14,
|
||||
PORT_PWM12,
|
||||
PORT_PWM8,
|
||||
PORT_PWM6,
|
||||
PORT_PWM5,
|
||||
PORT_PWM4,
|
||||
PORT_PWM3,
|
||||
PORT_PWM2,
|
||||
PORT_PWM1,
|
||||
PORT_PWM3CAP1,
|
||||
PORT_PWM4CAP1,
|
||||
PORT_PWM4CAP2,
|
||||
PORT_PWM5CAP1,
|
||||
PORT_PWM2CAP2,
|
||||
PORT_CAPTURE,
|
||||
};
|
||||
|
||||
#if !defined(BOARD_HAS_PWM)
|
||||
# error "board_config.h needs to define BOARD_HAS_PWM"
|
||||
#endif
|
||||
|
||||
// TODO: keep in sync with drivers/camera_capture
|
||||
#define PX4FMU_DEVICE_PATH "/dev/px4fmu"
|
||||
|
||||
static constexpr int PWM_OUT_MAX_INSTANCES{(DIRECT_PWM_OUTPUT_CHANNELS > 8) ? 2 : 1};
|
||||
@@ -99,29 +75,6 @@ extern pthread_mutex_t pwm_out_module_mutex;
|
||||
class PWMOut : public cdev::CDev, public OutputModuleInterface
|
||||
{
|
||||
public:
|
||||
enum Mode {
|
||||
MODE_NONE,
|
||||
MODE_1PWM,
|
||||
MODE_2PWM,
|
||||
MODE_2PWM2CAP,
|
||||
MODE_3PWM,
|
||||
MODE_3PWM1CAP,
|
||||
MODE_4PWM,
|
||||
MODE_4PWM1CAP,
|
||||
MODE_4PWM2CAP,
|
||||
MODE_5PWM,
|
||||
MODE_5PWM1CAP,
|
||||
MODE_6PWM,
|
||||
MODE_8PWM,
|
||||
MODE_12PWM,
|
||||
MODE_14PWM,
|
||||
MODE_4CAP,
|
||||
MODE_5CAP,
|
||||
MODE_6CAP,
|
||||
|
||||
MODE_NO_REQUEST
|
||||
};
|
||||
|
||||
PWMOut() = delete;
|
||||
explicit PWMOut(int instance = 0, uint8_t output_base = 0);
|
||||
|
||||
@@ -148,30 +101,20 @@ public:
|
||||
static bool trylock_module() { return (pthread_mutex_trylock(&pwm_out_module_mutex) == 0); }
|
||||
static void unlock_module() { pthread_mutex_unlock(&pwm_out_module_mutex); }
|
||||
|
||||
/** change the FMU mode of the running module */
|
||||
static int fmu_new_mode(PortMode new_mode);
|
||||
|
||||
static int test(const char *dev);
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
virtual int init();
|
||||
|
||||
int set_mode(Mode mode);
|
||||
Mode get_mode() const { return _mode; }
|
||||
uint32_t get_pwm_mask() const { return _pwm_mask; }
|
||||
void set_pwm_mask(uint32_t mask) { _pwm_mask = mask; }
|
||||
uint32_t get_alt_rate_channels() const { return _pwm_alt_rate_channels; }
|
||||
unsigned get_alt_rate() const { return _pwm_alt_rate; }
|
||||
unsigned get_default_rate() const { return _pwm_default_rate; }
|
||||
void request_mode(Mode new_mode);
|
||||
|
||||
static int set_i2c_bus_clock(unsigned bus, unsigned clock_hz);
|
||||
|
||||
static void capture_trampoline(void *context, uint32_t chan_index,
|
||||
hrt_abstime edge_time, uint32_t edge_state,
|
||||
uint32_t overflow);
|
||||
|
||||
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
unsigned num_outputs, unsigned num_control_groups_updated) override;
|
||||
|
||||
@@ -189,10 +132,6 @@ private:
|
||||
|
||||
MixingOutput _mixing_output{FMU_MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, true};
|
||||
|
||||
Mode _mode{MODE_NONE};
|
||||
|
||||
px4::atomic<Mode> _new_mode_request{MODE_NO_REQUEST};
|
||||
|
||||
uint32_t _backup_schedule_interval_us{1_s};
|
||||
|
||||
unsigned _pwm_default_rate{50};
|
||||
@@ -216,8 +155,6 @@ private:
|
||||
perf_counter_t _cycle_perf;
|
||||
perf_counter_t _interval_perf;
|
||||
|
||||
void capture_callback(uint32_t chan_index,
|
||||
hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow);
|
||||
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);
|
||||
@@ -229,8 +166,6 @@ private:
|
||||
static void sensor_reset(int ms);
|
||||
static void peripheral_reset(int ms);
|
||||
|
||||
int capture_ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
PWMOut(const PWMOut &) = delete;
|
||||
PWMOut operator=(const PWMOut &) = delete;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user