mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
pwm_out_sim cleanup
- move to ModuleBase - strip down to PWM 8 and 16 modes only - remove all dead code - implement missing pwm ioctls (current value, rates, etc) - default rate 50Hz -> 400Hz
This commit is contained in:
@@ -504,7 +504,7 @@ then
|
||||
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
then
|
||||
if pwm_out_sim mode_pwm16
|
||||
if pwm_out_sim start
|
||||
then
|
||||
else
|
||||
tune_control play -m ${TUNE_ERR}
|
||||
|
||||
@@ -56,7 +56,7 @@ const char *get_commands()
|
||||
"mc_pos_control start\n"
|
||||
"mc_att_control start\n"
|
||||
"sleep 1\n"
|
||||
"pwm_out_sim mode_pwm\n"
|
||||
"pwm_out_sim start\n"
|
||||
"param set RC1_MAX 2015\n"
|
||||
"param set RC1_MIN 996\n"
|
||||
"param set RC1_TRIM 1502\n"
|
||||
|
||||
@@ -13,7 +13,7 @@ dataman start
|
||||
|
||||
simulator start -s
|
||||
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
|
||||
|
||||
gyrosim start
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -55,7 +55,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -55,7 +55,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -54,7 +54,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -56,7 +56,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -61,7 +61,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
navigator start
|
||||
|
||||
@@ -57,7 +57,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sleep 1
|
||||
sensors start
|
||||
commander start
|
||||
|
||||
@@ -50,7 +50,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -68,7 +68,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start vtol
|
||||
|
||||
@@ -49,7 +49,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start vtol
|
||||
|
||||
@@ -70,7 +70,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start vtol
|
||||
|
||||
@@ -56,7 +56,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm16
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -51,7 +51,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -13,7 +13,7 @@ dataman start
|
||||
|
||||
simulator start -s
|
||||
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
|
||||
|
||||
gyrosim start
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -55,7 +55,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -55,7 +55,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -61,7 +61,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -71,7 +71,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -52,7 +52,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sleep 1
|
||||
sensors start
|
||||
commander start
|
||||
|
||||
@@ -59,7 +59,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
navigator start
|
||||
|
||||
@@ -53,7 +53,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sleep 1
|
||||
sensors start
|
||||
commander start
|
||||
|
||||
@@ -53,7 +53,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -63,7 +63,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start vtol
|
||||
|
||||
@@ -50,7 +50,7 @@ accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm16
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
land_detector start multicopter
|
||||
|
||||
@@ -35,7 +35,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
sensors start
|
||||
commander start
|
||||
navigator start
|
||||
|
||||
@@ -13,7 +13,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
|
||||
ver all
|
||||
|
||||
|
||||
@@ -13,7 +13,7 @@ barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
measairspeedsim start
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
|
||||
ver all
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ mc_pos_control start
|
||||
mc_att_control start
|
||||
land_detector start multicopter
|
||||
sleep 1
|
||||
pwm_out_sim mode_pwm
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 /startup/quad_x.main.mix
|
||||
list_devices
|
||||
list_files
|
||||
|
||||
@@ -18,7 +18,7 @@ mc_pos_control start
|
||||
mc_att_control start
|
||||
mavlink start -x -u 14577 -r 1000000
|
||||
navio_sysfs_rc_in start
|
||||
pwm_out_sim mode_pwm16
|
||||
pwm_out_sim start
|
||||
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x.main.mix
|
||||
logger start -t -b 200
|
||||
mavlink boot_complete
|
||||
|
||||
@@ -33,12 +33,6 @@
|
||||
px4_add_module(
|
||||
MODULE drivers__pwm_out_sim
|
||||
MAIN pwm_out_sim
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
pwm_out_sim.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
PWMSim.cpp
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,138 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef DRIVERS_PWM_OUT_SIM_PWMSIM_HPP_
|
||||
#define DRIVERS_PWM_OUT_SIM_PWMSIM_HPP_
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/device/device.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_mixer.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <lib/mixer/mixer.h>
|
||||
#include <px4_common.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_module.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_time.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
|
||||
class PWMSim : public device::CDev, public ModuleBase<PWMSim>
|
||||
{
|
||||
static constexpr uint32_t PWM_SIM_DISARMED_MAGIC = 900;
|
||||
static constexpr uint32_t PWM_SIM_FAILSAFE_MAGIC = 600;
|
||||
static constexpr uint32_t PWM_SIM_PWM_MIN_MAGIC = 1000;
|
||||
static constexpr uint32_t PWM_SIM_PWM_MAX_MAGIC = 2000;
|
||||
|
||||
public:
|
||||
|
||||
enum Mode {
|
||||
MODE_8PWM,
|
||||
MODE_16PWM,
|
||||
MODE_NONE
|
||||
};
|
||||
|
||||
PWMSim();
|
||||
virtual ~PWMSim() = default;
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int task_spawn(int argc, char *argv[]);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static PWMSim *instantiate(int argc, char *argv[]);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int custom_command(int argc, char *argv[]);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int print_usage(const char *reason = nullptr);
|
||||
|
||||
/** @see ModuleBase::run() */
|
||||
void run() override;
|
||||
|
||||
/** @see ModuleBase::print_status() */
|
||||
int print_status() override;
|
||||
|
||||
|
||||
int ioctl(device::file_t *filp, int cmd, unsigned long arg) override;
|
||||
|
||||
int set_pwm_rate(unsigned rate);
|
||||
|
||||
int set_mode(Mode mode);
|
||||
Mode get_mode() { return _mode; }
|
||||
|
||||
private:
|
||||
static constexpr unsigned MAX_ACTUATORS = 16;
|
||||
|
||||
Mode _mode{MODE_NONE};
|
||||
|
||||
int _update_rate{400};
|
||||
int _current_update_rate{0};
|
||||
|
||||
int _control_subs[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
|
||||
|
||||
px4_pollfd_struct_t _poll_fds[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
|
||||
unsigned _poll_fds_num{0};
|
||||
|
||||
int _armed_sub{-1};
|
||||
|
||||
actuator_outputs_s _actuator_outputs = {};
|
||||
orb_advert_t _outputs_pub{nullptr};
|
||||
|
||||
unsigned _num_outputs{0};
|
||||
|
||||
unsigned _pwm_min[MAX_ACTUATORS] {};
|
||||
unsigned _pwm_max[MAX_ACTUATORS] {};
|
||||
|
||||
uint32_t _groups_required{0};
|
||||
uint32_t _groups_subscribed{0};
|
||||
|
||||
bool _armed{false};
|
||||
bool _lockdown{false};
|
||||
bool _failsafe{false};
|
||||
|
||||
MixerGroup *_mixers{nullptr};
|
||||
|
||||
actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
|
||||
orb_id_t _control_topics[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
|
||||
|
||||
static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
|
||||
|
||||
void subscribe();
|
||||
|
||||
};
|
||||
|
||||
#endif /* DRIVERS_PWM_OUT_SIM_PWMSIM_HPP_ */
|
||||
File diff suppressed because it is too large
Load Diff
Reference in New Issue
Block a user