forked from Archive/PX4-Autopilot
helicopter: add switch to engage main motor
For helicopters it's useful (e.g. during bringup) to be able to disable the main rotor while the tail is still controlled to safely land.
This commit is contained in:
parent
f32d931117
commit
7e75b497ae
|
@ -29,4 +29,6 @@ uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGH
|
|||
uint8 photo_switch # Photo trigger switch
|
||||
uint8 video_switch # Photo trigger switch
|
||||
|
||||
uint8 engage_main_motor_switch # Engage the main motor (for helicopters)
|
||||
|
||||
uint32 switch_changes # number of switch changes
|
||||
|
|
|
@ -27,13 +27,14 @@ uint8 FUNCTION_FLTBTN_SLOT_3 = 23
|
|||
uint8 FUNCTION_FLTBTN_SLOT_4 = 24
|
||||
uint8 FUNCTION_FLTBTN_SLOT_5 = 25
|
||||
uint8 FUNCTION_FLTBTN_SLOT_6 = 26
|
||||
uint8 FUNCTION_ENGAGE_MAIN_MOTOR = 27
|
||||
|
||||
uint8 FUNCTION_FLTBTN_SLOT_COUNT = 6
|
||||
|
||||
uint64 timestamp_last_valid # Timestamp of last valid RC signal
|
||||
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
|
||||
uint8 channel_count # Number of valid channels
|
||||
int8[27] function # Functions mapping
|
||||
int8[28] function # Functions mapping
|
||||
uint8 rssi # Receive signal strength index
|
||||
bool signal_lost # Control signal lost, should be checked together with topic timeout
|
||||
uint32 frame_drop_count # Number of dropped frames
|
||||
|
|
|
@ -132,7 +132,8 @@ void ActuatorEffectivenessHelicopter::updateSetpoint(const matrix::Vector<float,
|
|||
const float collective_pitch = math::interpolateN(-control_sp(ControlAxis::THRUST_Z), _geometry.pitch_curve);
|
||||
|
||||
// actuator mapping
|
||||
actuator_sp(0) = throttle;
|
||||
actuator_sp(0) = mainMotorEnaged() ? throttle : NAN;
|
||||
|
||||
actuator_sp(1) = control_sp(ControlAxis::YAW)
|
||||
+ fabsf(collective_pitch) * _geometry.yaw_collective_pitch_scale
|
||||
+ throttle * _geometry.yaw_throttle_scale;
|
||||
|
@ -147,23 +148,16 @@ void ActuatorEffectivenessHelicopter::updateSetpoint(const matrix::Vector<float,
|
|||
}
|
||||
}
|
||||
|
||||
float ActuatorEffectivenessHelicopter::throttleSpoolupProgress()
|
||||
bool ActuatorEffectivenessHelicopter::mainMotorEnaged()
|
||||
{
|
||||
vehicle_status_s vehicle_status;
|
||||
manual_control_switches_s manual_control_switches;
|
||||
|
||||
if (_vehicle_status_sub.update(&vehicle_status)) {
|
||||
_armed = vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED;
|
||||
_armed_time = vehicle_status.armed_time;
|
||||
if (_manual_control_switches_sub.update(&manual_control_switches)) {
|
||||
_main_motor_engaged = manual_control_switches.engage_main_motor_switch == manual_control_switches_s::SWITCH_POS_NONE
|
||||
|| manual_control_switches.engage_main_motor_switch == manual_control_switches_s::SWITCH_POS_ON;
|
||||
}
|
||||
|
||||
const float time_since_arming = (hrt_absolute_time() - _armed_time) / 1e6f;
|
||||
const float spoolup_progress = time_since_arming / _geometry.spoolup_time;
|
||||
|
||||
if (_armed && spoolup_progress < 1.f) {
|
||||
return spoolup_progress;
|
||||
}
|
||||
|
||||
return 1.f;
|
||||
return _main_motor_engaged;
|
||||
}
|
||||
|
||||
float ActuatorEffectivenessHelicopter::throttleSpoolupProgress()
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/manual_control_switches.h>
|
||||
|
||||
class ActuatorEffectivenessHelicopter : public ModuleParams, public ActuatorEffectiveness
|
||||
{
|
||||
|
@ -77,6 +78,7 @@ public:
|
|||
ActuatorVector &actuator_sp) override;
|
||||
private:
|
||||
float throttleSpoolupProgress();
|
||||
bool mainMotorEnaged();
|
||||
|
||||
void updateParams() override;
|
||||
|
||||
|
@ -104,4 +106,7 @@ private:
|
|||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||
bool _armed{false};
|
||||
uint64_t _armed_time{0};
|
||||
|
||||
uORB::Subscription _manual_control_switches_sub{ORB_ID(manual_control_switches)};
|
||||
bool _main_motor_engaged{true};
|
||||
};
|
||||
|
|
|
@ -1855,6 +1855,34 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM2, 0);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0);
|
||||
|
||||
/**
|
||||
* RC channel to engage the main motor (for helicopters)
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Calibration
|
||||
* @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
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_ENG_MOT, 0);
|
||||
|
||||
/**
|
||||
* Failsafe channel PWM threshold.
|
||||
*
|
||||
|
@ -1985,6 +2013,22 @@ PARAM_DEFINE_FLOAT(RC_TRANS_TH, 0.75f);
|
|||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_GEAR_TH, 0.75f);
|
||||
|
||||
/**
|
||||
* Threshold for selecting main motor engage
|
||||
*
|
||||
* 0-1 indicate where in the full channel range the threshold sits
|
||||
* 0 : min
|
||||
* 1 : max
|
||||
* sign indicates polarity of comparison
|
||||
* positive : true when channel>th
|
||||
* negative : true when channel<th
|
||||
*
|
||||
* @min -1
|
||||
* @max 1
|
||||
* @group Radio Switches
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_ENG_MOT_TH, 0.75f);
|
||||
|
||||
/**
|
||||
* PWM input channel that provides RSSI.
|
||||
*
|
||||
|
|
|
@ -56,7 +56,8 @@ static bool operator ==(const manual_control_switches_s &a, const manual_control
|
|||
a.transition_switch == b.transition_switch &&
|
||||
a.gear_switch == b.gear_switch &&
|
||||
a.photo_switch == b.photo_switch &&
|
||||
a.video_switch == b.video_switch);
|
||||
a.video_switch == b.video_switch &&
|
||||
a.engage_main_motor_switch == b.engage_main_motor_switch);
|
||||
}
|
||||
|
||||
static bool operator !=(const manual_control_switches_s &a, const manual_control_switches_s &b) { return !(a == b); }
|
||||
|
@ -231,6 +232,8 @@ void RCUpdate::update_rc_functions()
|
|||
_rc.function[rc_channels_s::FUNCTION_PARAM_1 + i] = _parameters.rc_map_param[i] - 1;
|
||||
}
|
||||
|
||||
_rc.function[rc_channels_s::FUNCTION_ENGAGE_MAIN_MOTOR] = _param_rc_map_eng_mot.get() - 1;
|
||||
|
||||
map_flight_modes_buttons();
|
||||
}
|
||||
|
||||
|
@ -643,7 +646,8 @@ void RCUpdate::UpdateManualSwitches(const hrt_abstime ×tamp_sample)
|
|||
switches.arm_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_ARMSWITCH, _param_rc_armswitch_th.get());
|
||||
switches.transition_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_TRANSITION, _param_rc_trans_th.get());
|
||||
switches.gear_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_GEAR, _param_rc_gear_th.get());
|
||||
|
||||
switches.engage_main_motor_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_ENGAGE_MAIN_MOTOR,
|
||||
_param_rc_eng_mot_th.get());
|
||||
#if defined(ATL_MANTIS_RC_INPUT_HACKS)
|
||||
switches.photo_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_AUX_3, 0.5f);
|
||||
switches.video_switch = get_rc_sw2pos_position(rc_channels_s::FUNCTION_AUX_4, 0.5f);
|
||||
|
|
|
@ -226,6 +226,8 @@ public:
|
|||
(ParamInt<px4::params::RC_MAP_AUX5>) _param_rc_map_aux5,
|
||||
(ParamInt<px4::params::RC_MAP_AUX6>) _param_rc_map_aux6,
|
||||
|
||||
(ParamInt<px4::params::RC_MAP_ENG_MOT>) _param_rc_map_eng_mot,
|
||||
|
||||
(ParamInt<px4::params::RC_FAILS_THR>) _param_rc_fails_thr,
|
||||
|
||||
(ParamFloat<px4::params::RC_LOITER_TH>) _param_rc_loiter_th,
|
||||
|
@ -235,6 +237,7 @@ public:
|
|||
(ParamFloat<px4::params::RC_TRANS_TH>) _param_rc_trans_th,
|
||||
(ParamFloat<px4::params::RC_GEAR_TH>) _param_rc_gear_th,
|
||||
(ParamFloat<px4::params::RC_RETURN_TH>) _param_rc_return_th,
|
||||
(ParamFloat<px4::params::RC_ENG_MOT_TH>) _param_rc_eng_mot_th,
|
||||
|
||||
(ParamInt<px4::params::RC_CHAN_CNT>) _param_rc_chan_cnt
|
||||
)
|
||||
|
|
Loading…
Reference in New Issue