Browse Source

AirModeYaw - Change airmode type from bool to int

sbg
bresch 7 years ago committed by Beat Küng
parent
commit
7cc00f41d2
  1. 10
      src/drivers/linux_pwm_out/linux_pwm_out.cpp
  2. 4
      src/drivers/pwm_out_sim/PWMSim.cpp
  3. 2
      src/drivers/pwm_out_sim/PWMSim.hpp
  4. 11
      src/drivers/px4fmu/fmu.cpp
  5. 10
      src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
  6. 4
      src/drivers/uavcan/uavcan_main.cpp
  7. 2
      src/drivers/uavcan/uavcan_main.hpp
  8. 10
      src/lib/mixer/mixer.h
  9. 2
      src/lib/mixer/mixer_group.cpp
  10. 6
      src/lib/mixer/mixer_multirotor.cpp
  11. 6
      src/modules/mc_att_control/mc_att_control_params.c
  12. 5
      src/modules/px4iofirmware/protocol.h

10
src/drivers/linux_pwm_out/linux_pwm_out.cpp

@ -116,7 +116,7 @@ static void subscribe();
static void task_main(int argc, char *argv[]); static void task_main(int argc, char *argv[]);
static void update_params(bool &airmode); static void update_params(int32_t &airmode);
/* mixer initialization */ /* mixer initialization */
int initialize_mixer(const char *mixer_filename); int initialize_mixer(const char *mixer_filename);
@ -135,15 +135,13 @@ int mixer_control_callback(uintptr_t handle,
} }
void update_params(bool &airmode) void update_params(int32_t &airmode)
{ {
// multicopter air-mode // multicopter air-mode
param_t param_handle = param_find("MC_AIRMODE"); param_t param_handle = param_find("MC_AIRMODE");
if (param_handle != PARAM_INVALID) { if (param_handle != PARAM_INVALID) {
int32_t val; param_get(param_handle, (int32_t *)&airmode);
param_get(param_handle, &val);
airmode = val > 0;
} }
} }
@ -257,7 +255,7 @@ void task_main(int argc, char *argv[])
// subscribe and set up polling // subscribe and set up polling
subscribe(); subscribe();
bool airmode = false; int32_t airmode = false;
update_params(airmode); update_params(airmode);
int params_sub = orb_subscribe(ORB_ID(parameter_update)); int params_sub = orb_subscribe(ORB_ID(parameter_update));

4
src/drivers/pwm_out_sim/PWMSim.cpp

@ -146,9 +146,7 @@ void PWMSim::update_params()
param_t param_handle = param_find("MC_AIRMODE"); param_t param_handle = param_find("MC_AIRMODE");
if (param_handle != PARAM_INVALID) { if (param_handle != PARAM_INVALID) {
int32_t val; param_get(param_handle, &_airmode);
param_get(param_handle, &val);
_airmode = val > 0;
} }
} }

2
src/drivers/pwm_out_sim/PWMSim.hpp

@ -131,7 +131,7 @@ private:
actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {}; actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
orb_id_t _control_topics[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {}; orb_id_t _control_topics[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
bool _airmode{false}; ///< multicopter air-mode int32_t _airmode{0}; ///< multicopter air-mode
perf_counter_t _perf_control_latency; perf_counter_t _perf_control_latency;

11
src/drivers/px4fmu/fmu.cpp

@ -237,7 +237,7 @@ private:
float _mot_t_max; ///< maximum rise time for motor (slew rate limiting) float _mot_t_max; ///< maximum rise time for motor (slew rate limiting)
float _thr_mdl_fac; ///< thrust to pwm modelling factor float _thr_mdl_fac; ///< thrust to pwm modelling factor
bool _airmode; ///< multicopter air-mode int32_t _airmode; ///< multicopter air-mode
MotorOrdering _motor_ordering; MotorOrdering _motor_ordering;
perf_counter_t _perf_control_latency; perf_counter_t _perf_control_latency;
@ -321,7 +321,7 @@ PX4FMU::PX4FMU(bool run_as_task) :
_to_mixer_status(nullptr), _to_mixer_status(nullptr),
_mot_t_max(0.0f), _mot_t_max(0.0f),
_thr_mdl_fac(0.0f), _thr_mdl_fac(0.0f),
_airmode(false), _airmode(0),
_motor_ordering(MotorOrdering::PX4), _motor_ordering(MotorOrdering::PX4),
_perf_control_latency(perf_alloc(PC_ELAPSED, "fmu control latency")) _perf_control_latency(perf_alloc(PC_ELAPSED, "fmu control latency"))
{ {
@ -1195,7 +1195,7 @@ PX4FMU::cycle()
} }
} }
/* overwrite outputs in case of lockdown with disarmed PWM values */ /* overwrite outputs in case of lockdown or parachute triggering with disarmed PWM values */
if (_armed.lockdown || _armed.manual_lockdown) { if (_armed.lockdown || _armed.manual_lockdown) {
for (size_t i = 0; i < mixed_num_outputs; i++) { for (size_t i = 0; i < mixed_num_outputs; i++) {
pwm_limited[i] = _disarmed_pwm[i]; pwm_limited[i] = _disarmed_pwm[i];
@ -1382,10 +1382,7 @@ void PX4FMU::update_params()
param_handle = param_find("MC_AIRMODE"); param_handle = param_find("MC_AIRMODE");
if (param_handle != PARAM_INVALID) { if (param_handle != PARAM_INVALID) {
int32_t val; param_get(param_handle, &_airmode);
param_get(param_handle, &val);
_airmode = val > 0;
PX4_DEBUG("%s: %d", "MC_AIRMODE", _airmode);
} }
// motor ordering // motor ordering

10
src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp

@ -138,7 +138,7 @@ static void subscribe();
static void task_main(int argc, char *argv[]); static void task_main(int argc, char *argv[]);
static void update_params(bool &airmode); static void update_params(int32_t &airmode);
int initialize_mixer(const char *mixer_filename); int initialize_mixer(const char *mixer_filename);
@ -162,15 +162,13 @@ int mixer_control_callback(uintptr_t handle,
return 0; return 0;
} }
void update_params(bool &airmode) void update_params(int32_t &airmode)
{ {
// multicopter air-mode // multicopter air-mode
param_t param_handle = param_find("MC_AIRMODE"); param_t param_handle = param_find("MC_AIRMODE");
if (param_handle != PARAM_INVALID) { if (param_handle != PARAM_INVALID) {
int32_t val; param_get(param_handle, &airmode);
param_get(param_handle, &val);
airmode = val > 0;
} }
} }
@ -357,7 +355,7 @@ void task_main(int argc, char *argv[])
// subscribe and set up polling // subscribe and set up polling
subscribe(); subscribe();
bool airmode = false; int32_t airmode = 0;
update_params(airmode); update_params(airmode);
int params_sub = orb_subscribe(ORB_ID(parameter_update)); int params_sub = orb_subscribe(ORB_ID(parameter_update));

4
src/drivers/uavcan/uavcan_main.cpp

@ -428,9 +428,7 @@ void UavcanNode::update_params()
param_t param_handle = param_find("MC_AIRMODE"); param_t param_handle = param_find("MC_AIRMODE");
if (param_handle != PARAM_INVALID) { if (param_handle != PARAM_INVALID) {
int32_t val; param_get(param_handle, &_airmode);
param_get(param_handle, &val);
_airmode = val > 0;
} }
} }

2
src/drivers/uavcan/uavcan_main.hpp

@ -210,7 +210,7 @@ private:
perf_counter_t _perf_control_latency; perf_counter_t _perf_control_latency;
bool _airmode = false; int32_t _airmode = 0;
// index into _poll_fds for each _control_subs handle // index into _poll_fds for each _control_subs handle
uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN];

10
src/lib/mixer/mixer.h

@ -221,9 +221,9 @@ public:
/** /**
* @brief Set airmode. Airmode allows the mixer to increase the total thrust in order to unsaturate the motors. * @brief Set airmode. Airmode allows the mixer to increase the total thrust in order to unsaturate the motors.
* *
* @param[in] airmode De/-activate airmode by setting it to false/true * @param[in] airmode Select airmode type (0 = disabled, 1 = roll/pitch, 2 = roll/pitch/yaw)
*/ */
virtual void set_airmode(bool airmode) {}; virtual void set_airmode(int32_t airmode) {};
protected: protected:
/** client-supplied callback used when fetching control values */ /** client-supplied callback used when fetching control values */
@ -419,7 +419,7 @@ public:
*/ */
virtual void set_thrust_factor(float val); virtual void set_thrust_factor(float val);
virtual void set_airmode(bool airmode); virtual void set_airmode(uint32_t airmode);
private: private:
Mixer *_first; /**< linked list of mixers */ Mixer *_first; /**< linked list of mixers */
@ -668,7 +668,7 @@ public:
*/ */
virtual void set_thrust_factor(float val) {_thrust_factor = val;} virtual void set_thrust_factor(float val) {_thrust_factor = val;}
virtual void set_airmode(bool airmode); virtual void set_airmode(uint32_t airmode);
union saturation_status { union saturation_status {
struct { struct {
@ -695,7 +695,7 @@ private:
float _delta_out_max; float _delta_out_max;
float _thrust_factor; float _thrust_factor;
bool _airmode; uint32_t _airmode;
void update_saturation_status(unsigned index, bool clipping_high, bool clipping_low); void update_saturation_status(unsigned index, bool clipping_high, bool clipping_low);
saturation_status _saturation_status; saturation_status _saturation_status;

2
src/lib/mixer/mixer_group.cpp

@ -188,7 +188,7 @@ MixerGroup::set_thrust_factor(float val)
} }
void void
MixerGroup::set_airmode(bool airmode) MixerGroup::set_airmode(int32_t airmode)
{ {
Mixer *mixer = _first; Mixer *mixer = _first;

6
src/lib/mixer/mixer_multirotor.cpp

@ -72,7 +72,7 @@ MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
_idle_speed(-1.0f + idle_speed * 2.0f), /* shift to output range here to avoid runtime calculation */ _idle_speed(-1.0f + idle_speed * 2.0f), /* shift to output range here to avoid runtime calculation */
_delta_out_max(0.0f), _delta_out_max(0.0f),
_thrust_factor(0.0f), _thrust_factor(0.0f),
_airmode(false), _airmode(0),
_rotor_count(_config_rotor_count[(MultirotorGeometryUnderlyingType)geometry]), _rotor_count(_config_rotor_count[(MultirotorGeometryUnderlyingType)geometry]),
_rotors(_config_index[(MultirotorGeometryUnderlyingType)geometry]), _rotors(_config_index[(MultirotorGeometryUnderlyingType)geometry]),
_outputs_prev(new float[_rotor_count]) _outputs_prev(new float[_rotor_count])
@ -214,7 +214,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
boost = 1.0f - ((max_out - thrust) * roll_pitch_scale + thrust); boost = 1.0f - ((max_out - thrust) * roll_pitch_scale + thrust);
} }
if (!_airmode) { if (_airmode == 0) {
// disable positive boosting if not in air-mode // disable positive boosting if not in air-mode
// boosting can only be positive when min_out < 0.0 // boosting can only be positive when min_out < 0.0
// roll_pitch_scale is reduced accordingly // roll_pitch_scale is reduced accordingly
@ -425,7 +425,7 @@ MultirotorMixer::update_saturation_status(unsigned index, bool clipping_high, bo
} }
void void
MultirotorMixer::set_airmode(bool airmode) MultirotorMixer::set_airmode(int32_t airmode)
{ {
_airmode = airmode; _airmode = airmode;
} }

6
src/modules/mc_att_control/mc_att_control_params.c

@ -572,7 +572,11 @@ PARAM_DEFINE_FLOAT(MC_DTERM_CUTOFF, 30.f);
* This function should be disabled during tuning as it will help the controller * This function should be disabled during tuning as it will help the controller
* to diverge if the closed-loop is unstable. * to diverge if the closed-loop is unstable.
* *
* @boolean * 0 = Disabled, 1 = Roll/Pitch, 2 = Roll/Pitch/Yaw
*
* @min 0
* @max 2
* @decimal 0
* @group Multicopter Attitude Control * @group Multicopter Attitude Control
*/ */
PARAM_DEFINE_INT32(MC_AIRMODE, 0); PARAM_DEFINE_INT32(MC_AIRMODE, 0);

5
src/modules/px4iofirmware/protocol.h

@ -234,11 +234,12 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_MOTOR_SLEW_MAX 24 /* max motor slew rate */ #define PX4IO_P_SETUP_MOTOR_SLEW_MAX 24 /* max motor slew rate */
#define PX4IO_P_SETUP_AIRMODE 27 /* air-mode */
#define PX4IO_P_SETUP_THR_MDL_FAC 25 /* factor for modelling static pwm output to thrust relationship */ #define PX4IO_P_SETUP_THR_MDL_FAC 25 /* factor for modelling static pwm output to thrust relationship */
#define PX4IO_P_SETUP_THERMAL 26 /* thermal management */ #define PX4IO_P_SETUP_THERMAL 26 /* thermal management */
#define PX4IO_P_SETUP_AIRMODE 27 /* air-mode */
#define PX4IO_THERMAL_IGNORE UINT16_MAX #define PX4IO_THERMAL_IGNORE UINT16_MAX
#define PX4IO_THERMAL_OFF 0 #define PX4IO_THERMAL_OFF 0
#define PX4IO_THERMAL_FULL 10000 #define PX4IO_THERMAL_FULL 10000

Loading…
Cancel
Save