forked from Archive/PX4-Autopilot
renamed EASY to POSHOLD and SEATBELT to ALTHOLD
This commit is contained in:
parent
6a7b104c2b
commit
269800b48c
|
@ -638,11 +638,11 @@ BlinkM::led()
|
||||||
|
|
||||||
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
|
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
|
||||||
/* indicate main control state */
|
/* indicate main control state */
|
||||||
if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
|
if (vehicle_status_raw.main_state == MAIN_STATE_POSHOLD)
|
||||||
led_color_4 = LED_GREEN;
|
led_color_4 = LED_GREEN;
|
||||||
else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
|
else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
|
||||||
led_color_4 = LED_BLUE;
|
led_color_4 = LED_BLUE;
|
||||||
else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
|
else if (vehicle_status_raw.main_state == MAIN_STATE_ALTHOLD)
|
||||||
led_color_4 = LED_YELLOW;
|
led_color_4 = LED_YELLOW;
|
||||||
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
|
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
|
||||||
led_color_4 = LED_WHITE;
|
led_color_4 = LED_WHITE;
|
||||||
|
|
|
@ -434,13 +434,13 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
||||||
/* MANUAL */
|
/* MANUAL */
|
||||||
main_res = main_state_transition(status, MAIN_STATE_MANUAL);
|
main_res = main_state_transition(status, MAIN_STATE_MANUAL);
|
||||||
|
|
||||||
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
|
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTHOLD) {
|
||||||
/* SEATBELT */
|
/* ALTHOLD */
|
||||||
main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
|
main_res = main_state_transition(status, MAIN_STATE_ALTHOLD);
|
||||||
|
|
||||||
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
|
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSHOLD) {
|
||||||
/* EASY */
|
/* POSHOLD */
|
||||||
main_res = main_state_transition(status, MAIN_STATE_EASY);
|
main_res = main_state_transition(status, MAIN_STATE_POSHOLD);
|
||||||
|
|
||||||
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
|
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
|
||||||
/* AUTO */
|
/* AUTO */
|
||||||
|
@ -455,8 +455,8 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
||||||
|
|
||||||
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
|
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
|
||||||
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
|
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
|
||||||
/* EASY */
|
/* POSHOLD */
|
||||||
main_res = main_state_transition(status, MAIN_STATE_EASY);
|
main_res = main_state_transition(status, MAIN_STATE_POSHOLD);
|
||||||
|
|
||||||
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
|
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
|
||||||
/* MANUAL */
|
/* MANUAL */
|
||||||
|
@ -628,8 +628,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
|
|
||||||
char *main_states_str[MAIN_STATE_MAX];
|
char *main_states_str[MAIN_STATE_MAX];
|
||||||
main_states_str[0] = "MANUAL";
|
main_states_str[0] = "MANUAL";
|
||||||
main_states_str[1] = "SEATBELT";
|
main_states_str[1] = "ALTHOLD";
|
||||||
main_states_str[2] = "EASY";
|
main_states_str[2] = "POSHOLD";
|
||||||
main_states_str[3] = "AUTO";
|
main_states_str[3] = "AUTO";
|
||||||
|
|
||||||
char *arming_states_str[ARMING_STATE_MAX];
|
char *arming_states_str[ARMING_STATE_MAX];
|
||||||
|
@ -1299,8 +1299,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
}
|
}
|
||||||
|
|
||||||
// TODO remove this hack
|
// TODO remove this hack
|
||||||
/* flight termination in manual mode if assisted switch is on easy position */
|
/* flight termination in manual mode if assisted switch is on poshold position */
|
||||||
if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.easy_switch == SWITCH_POS_ON) {
|
if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.poshold_switch == SWITCH_POS_ON) {
|
||||||
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
|
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
|
||||||
tune_positive(armed.armed);
|
tune_positive(armed.armed);
|
||||||
}
|
}
|
||||||
|
@ -1557,25 +1557,25 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case SWITCH_POS_MIDDLE: // ASSISTED
|
case SWITCH_POS_MIDDLE: // ASSISTED
|
||||||
if (sp_man->easy_switch == SWITCH_POS_ON) {
|
if (sp_man->poshold_switch == SWITCH_POS_ON) {
|
||||||
res = main_state_transition(status, MAIN_STATE_EASY);
|
res = main_state_transition(status, MAIN_STATE_POSHOLD);
|
||||||
|
|
||||||
if (res != TRANSITION_DENIED) {
|
if (res != TRANSITION_DENIED) {
|
||||||
break; // changed successfully or already in this state
|
break; // changed successfully or already in this state
|
||||||
}
|
}
|
||||||
|
|
||||||
// else fallback to SEATBELT
|
// else fallback to ALTHOLD
|
||||||
print_reject_mode(status, "EASY");
|
print_reject_mode(status, "POSHOLD");
|
||||||
}
|
}
|
||||||
|
|
||||||
res = main_state_transition(status, MAIN_STATE_SEATBELT);
|
res = main_state_transition(status, MAIN_STATE_ALTHOLD);
|
||||||
|
|
||||||
if (res != TRANSITION_DENIED) {
|
if (res != TRANSITION_DENIED) {
|
||||||
break; // changed successfully or already in this mode
|
break; // changed successfully or already in this mode
|
||||||
}
|
}
|
||||||
|
|
||||||
if (sp_man->easy_switch != SWITCH_POS_ON) {
|
if (sp_man->poshold_switch != SWITCH_POS_ON) {
|
||||||
print_reject_mode(status, "SEATBELT");
|
print_reject_mode(status, "ALTHOLD");
|
||||||
}
|
}
|
||||||
|
|
||||||
// else fallback to MANUAL
|
// else fallback to MANUAL
|
||||||
|
@ -1590,9 +1590,9 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
|
||||||
break; // changed successfully or already in this state
|
break; // changed successfully or already in this state
|
||||||
}
|
}
|
||||||
|
|
||||||
// else fallback to SEATBELT (EASY likely will not work too)
|
// else fallback to ALTHOLD (POSHOLD likely will not work too)
|
||||||
print_reject_mode(status, "AUTO");
|
print_reject_mode(status, "AUTO");
|
||||||
res = main_state_transition(status, MAIN_STATE_SEATBELT);
|
res = main_state_transition(status, MAIN_STATE_ALTHOLD);
|
||||||
|
|
||||||
if (res != TRANSITION_DENIED) {
|
if (res != TRANSITION_DENIED) {
|
||||||
break; // changed successfully or already in this state
|
break; // changed successfully or already in this state
|
||||||
|
@ -1638,7 +1638,7 @@ set_control_mode()
|
||||||
control_mode.flag_control_velocity_enabled = false;
|
control_mode.flag_control_velocity_enabled = false;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAIN_STATE_SEATBELT:
|
case MAIN_STATE_ALTHOLD:
|
||||||
control_mode.flag_control_manual_enabled = true;
|
control_mode.flag_control_manual_enabled = true;
|
||||||
control_mode.flag_control_auto_enabled = false;
|
control_mode.flag_control_auto_enabled = false;
|
||||||
control_mode.flag_control_rates_enabled = true;
|
control_mode.flag_control_rates_enabled = true;
|
||||||
|
@ -1649,7 +1649,7 @@ set_control_mode()
|
||||||
control_mode.flag_control_velocity_enabled = false;
|
control_mode.flag_control_velocity_enabled = false;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAIN_STATE_EASY:
|
case MAIN_STATE_POSHOLD:
|
||||||
control_mode.flag_control_manual_enabled = true;
|
control_mode.flag_control_manual_enabled = true;
|
||||||
control_mode.flag_control_auto_enabled = false;
|
control_mode.flag_control_auto_enabled = false;
|
||||||
control_mode.flag_control_rates_enabled = true;
|
control_mode.flag_control_rates_enabled = true;
|
||||||
|
|
|
@ -317,34 +317,34 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
|
||||||
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
||||||
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
||||||
|
|
||||||
// MANUAL to SEATBELT.
|
// MANUAL to ALTHOLD.
|
||||||
current_state.main_state = MAIN_STATE_MANUAL;
|
current_state.main_state = MAIN_STATE_MANUAL;
|
||||||
current_state.condition_local_altitude_valid = true;
|
current_state.condition_local_altitude_valid = true;
|
||||||
new_main_state = MAIN_STATE_SEATBELT;
|
new_main_state = MAIN_STATE_ALTHOLD;
|
||||||
ut_assert("tranisition: manual to seatbelt",
|
ut_assert("tranisition: manual to althold",
|
||||||
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
||||||
ut_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
|
ut_assert("new state: althold", MAIN_STATE_ALTHOLD == current_state.main_state);
|
||||||
|
|
||||||
// MANUAL to SEATBELT, invalid local altitude.
|
// MANUAL to ALTHOLD, invalid local altitude.
|
||||||
current_state.main_state = MAIN_STATE_MANUAL;
|
current_state.main_state = MAIN_STATE_MANUAL;
|
||||||
current_state.condition_local_altitude_valid = false;
|
current_state.condition_local_altitude_valid = false;
|
||||||
new_main_state = MAIN_STATE_SEATBELT;
|
new_main_state = MAIN_STATE_ALTHOLD;
|
||||||
ut_assert("no transition: invalid local altitude",
|
ut_assert("no transition: invalid local altitude",
|
||||||
TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state));
|
TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state));
|
||||||
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
||||||
|
|
||||||
// MANUAL to EASY.
|
// MANUAL to POSHOLD.
|
||||||
current_state.main_state = MAIN_STATE_MANUAL;
|
current_state.main_state = MAIN_STATE_MANUAL;
|
||||||
current_state.condition_local_position_valid = true;
|
current_state.condition_local_position_valid = true;
|
||||||
new_main_state = MAIN_STATE_EASY;
|
new_main_state = MAIN_STATE_POSHOLD;
|
||||||
ut_assert("transition: manual to easy",
|
ut_assert("transition: manual to poshold",
|
||||||
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state));
|
||||||
ut_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
|
ut_assert("current state: poshold", MAIN_STATE_POSHOLD == current_state.main_state);
|
||||||
|
|
||||||
// MANUAL to EASY, invalid local position.
|
// MANUAL to POSHOLD, invalid local position.
|
||||||
current_state.main_state = MAIN_STATE_MANUAL;
|
current_state.main_state = MAIN_STATE_MANUAL;
|
||||||
current_state.condition_local_position_valid = false;
|
current_state.condition_local_position_valid = false;
|
||||||
new_main_state = MAIN_STATE_EASY;
|
new_main_state = MAIN_STATE_POSHOLD;
|
||||||
ut_assert("no transition: invalid position",
|
ut_assert("no transition: invalid position",
|
||||||
TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state));
|
TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state));
|
||||||
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
|
||||||
|
|
|
@ -12,8 +12,8 @@
|
||||||
|
|
||||||
enum PX4_CUSTOM_MAIN_MODE {
|
enum PX4_CUSTOM_MAIN_MODE {
|
||||||
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
|
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
|
||||||
PX4_CUSTOM_MAIN_MODE_SEATBELT,
|
PX4_CUSTOM_MAIN_MODE_ALTHOLD,
|
||||||
PX4_CUSTOM_MAIN_MODE_EASY,
|
PX4_CUSTOM_MAIN_MODE_POSHOLD,
|
||||||
PX4_CUSTOM_MAIN_MODE_AUTO,
|
PX4_CUSTOM_MAIN_MODE_AUTO,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -215,7 +215,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||||
ret = TRANSITION_CHANGED;
|
ret = TRANSITION_CHANGED;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAIN_STATE_SEATBELT:
|
case MAIN_STATE_ALTHOLD:
|
||||||
|
|
||||||
/* need at minimum altitude estimate */
|
/* need at minimum altitude estimate */
|
||||||
if (!status->is_rotary_wing ||
|
if (!status->is_rotary_wing ||
|
||||||
|
@ -226,7 +226,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAIN_STATE_EASY:
|
case MAIN_STATE_POSHOLD:
|
||||||
|
|
||||||
/* need at minimum local position estimate */
|
/* need at minimum local position estimate */
|
||||||
if (status->condition_local_position_valid ||
|
if (status->condition_local_position_valid ||
|
||||||
|
|
|
@ -229,8 +229,8 @@ void BlockMultiModeBacksideAutopilot::update()
|
||||||
_actuators.control[CH_RDR] = _manual.yaw;
|
_actuators.control[CH_RDR] = _manual.yaw;
|
||||||
_actuators.control[CH_THR] = _manual.throttle;
|
_actuators.control[CH_THR] = _manual.throttle;
|
||||||
|
|
||||||
} else if (_status.main_state == MAIN_STATE_SEATBELT ||
|
} else if (_status.main_state == MAIN_STATE_ALTHOLD ||
|
||||||
_status.main_state == MAIN_STATE_EASY /* TODO, implement easy */) {
|
_status.main_state == MAIN_STATE_POSHOLD /* TODO, implement easy */) {
|
||||||
|
|
||||||
// calculate velocity, XXX should be airspeed, but using ground speed for now
|
// calculate velocity, XXX should be airspeed, but using ground speed for now
|
||||||
// for the purpose of control we will limit the velocity feedback between
|
// for the purpose of control we will limit the velocity feedback between
|
||||||
|
|
|
@ -153,7 +153,7 @@ private:
|
||||||
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
|
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
|
||||||
|
|
||||||
/** manual control states */
|
/** manual control states */
|
||||||
float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
|
float _althold_hold_heading; /**< heading the system should hold in althold mode */
|
||||||
double _loiter_hold_lat;
|
double _loiter_hold_lat;
|
||||||
double _loiter_hold_lon;
|
double _loiter_hold_lon;
|
||||||
float _loiter_hold_alt;
|
float _loiter_hold_alt;
|
||||||
|
@ -1051,16 +1051,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
_att_sp.roll_reset_integral = true;
|
_att_sp.roll_reset_integral = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
} else if (0/* easy mode enabled */) {
|
} else if (0/* poshold mode enabled */) {
|
||||||
|
|
||||||
/** EASY FLIGHT **/
|
/** POSHOLD FLIGHT **/
|
||||||
|
|
||||||
if (0/* switched from another mode to easy */) {
|
if (0/* switched from another mode to poshold */) {
|
||||||
_seatbelt_hold_heading = _att.yaw;
|
_althold_hold_heading = _att.yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (0/* easy on and manual control yaw non-zero */) {
|
if (0/* poshold on and manual control yaw non-zero */) {
|
||||||
_seatbelt_hold_heading = _att.yaw + _manual.yaw;
|
_althold_hold_heading = _att.yaw + _manual.yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
//XXX not used
|
//XXX not used
|
||||||
|
@ -1073,39 +1073,39 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
// climb_out = true;
|
// climb_out = true;
|
||||||
// }
|
// }
|
||||||
|
|
||||||
/* if in seatbelt mode, set airspeed based on manual control */
|
/* if in althold mode, set airspeed based on manual control */
|
||||||
|
|
||||||
// XXX check if ground speed undershoot should be applied here
|
// XXX check if ground speed undershoot should be applied here
|
||||||
float seatbelt_airspeed = _parameters.airspeed_min +
|
float althold_airspeed = _parameters.airspeed_min +
|
||||||
(_parameters.airspeed_max - _parameters.airspeed_min) *
|
(_parameters.airspeed_max - _parameters.airspeed_min) *
|
||||||
_manual.throttle;
|
_manual.throttle;
|
||||||
|
|
||||||
_l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
|
_l1_control.navigate_heading(_althold_hold_heading, _att.yaw, ground_speed);
|
||||||
_att_sp.roll_body = _l1_control.nav_roll();
|
_att_sp.roll_body = _l1_control.nav_roll();
|
||||||
_att_sp.yaw_body = _l1_control.nav_bearing();
|
_att_sp.yaw_body = _l1_control.nav_bearing();
|
||||||
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
|
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
|
||||||
seatbelt_airspeed,
|
althold_airspeed,
|
||||||
_airspeed.indicated_airspeed_m_s, eas2tas,
|
_airspeed.indicated_airspeed_m_s, eas2tas,
|
||||||
false, _parameters.pitch_limit_min,
|
false, _parameters.pitch_limit_min,
|
||||||
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
|
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
|
||||||
_parameters.pitch_limit_min, _parameters.pitch_limit_max);
|
_parameters.pitch_limit_min, _parameters.pitch_limit_max);
|
||||||
|
|
||||||
} else if (0/* seatbelt mode enabled */) {
|
} else if (0/* althold mode enabled */) {
|
||||||
|
|
||||||
/** SEATBELT FLIGHT **/
|
/** ALTHOLD FLIGHT **/
|
||||||
|
|
||||||
if (0/* switched from another mode to seatbelt */) {
|
if (0/* switched from another mode to althold */) {
|
||||||
_seatbelt_hold_heading = _att.yaw;
|
_althold_hold_heading = _att.yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (0/* seatbelt on and manual control yaw non-zero */) {
|
if (0/* althold on and manual control yaw non-zero */) {
|
||||||
_seatbelt_hold_heading = _att.yaw + _manual.yaw;
|
_althold_hold_heading = _att.yaw + _manual.yaw;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* if in seatbelt mode, set airspeed based on manual control */
|
/* if in althold mode, set airspeed based on manual control */
|
||||||
|
|
||||||
// XXX check if ground speed undershoot should be applied here
|
// XXX check if ground speed undershoot should be applied here
|
||||||
float seatbelt_airspeed = _parameters.airspeed_min +
|
float althold_airspeed = _parameters.airspeed_min +
|
||||||
(_parameters.airspeed_max - _parameters.airspeed_min) *
|
(_parameters.airspeed_max - _parameters.airspeed_min) *
|
||||||
_manual.throttle;
|
_manual.throttle;
|
||||||
|
|
||||||
|
@ -1124,11 +1124,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
climb_out = true;
|
climb_out = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
_l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
|
_l1_control.navigate_heading(_althold_hold_heading, _att.yaw, ground_speed);
|
||||||
_att_sp.roll_body = _manual.roll;
|
_att_sp.roll_body = _manual.roll;
|
||||||
_att_sp.yaw_body = _manual.yaw;
|
_att_sp.yaw_body = _manual.yaw;
|
||||||
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
|
_tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
|
||||||
seatbelt_airspeed,
|
althold_airspeed,
|
||||||
_airspeed.indicated_airspeed_m_s, eas2tas,
|
_airspeed.indicated_airspeed_m_s, eas2tas,
|
||||||
climb_out, _parameters.pitch_limit_min,
|
climb_out, _parameters.pitch_limit_min,
|
||||||
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
|
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
|
||||||
|
|
|
@ -124,13 +124,13 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
|
||||||
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
|
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
|
||||||
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
|
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
|
||||||
|
|
||||||
} else if (status->main_state == MAIN_STATE_SEATBELT) {
|
} else if (status->main_state == MAIN_STATE_ALTHOLD) {
|
||||||
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
|
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||||
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT;
|
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTHOLD;
|
||||||
|
|
||||||
} else if (status->main_state == MAIN_STATE_EASY) {
|
} else if (status->main_state == MAIN_STATE_POSHOLD) {
|
||||||
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
|
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||||
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_EASY;
|
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSHOLD;
|
||||||
|
|
||||||
} else if (status->main_state == MAIN_STATE_AUTO) {
|
} else if (status->main_state == MAIN_STATE_AUTO) {
|
||||||
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
|
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
|
||||||
|
|
|
@ -98,7 +98,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
|
||||||
/**
|
/**
|
||||||
* Maximum vertical velocity
|
* Maximum vertical velocity
|
||||||
*
|
*
|
||||||
* Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY).
|
* Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTHOLD, POSHOLD).
|
||||||
*
|
*
|
||||||
* @unit m/s
|
* @unit m/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
|
@ -109,7 +109,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
|
||||||
/**
|
/**
|
||||||
* Vertical velocity feed forward
|
* Vertical velocity feed forward
|
||||||
*
|
*
|
||||||
* Feed forward weight for altitude control in stabilized modes (SEATBELT, EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
* Feed forward weight for altitude control in stabilized modes (ALTHOLD, POSHOLD). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
|
@ -154,7 +154,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
|
||||||
/**
|
/**
|
||||||
* Maximum horizontal velocity
|
* Maximum horizontal velocity
|
||||||
*
|
*
|
||||||
* Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY).
|
* Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSHOLD).
|
||||||
*
|
*
|
||||||
* @unit m/s
|
* @unit m/s
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
|
@ -165,7 +165,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
|
||||||
/**
|
/**
|
||||||
* Horizontal velocity feed forward
|
* Horizontal velocity feed forward
|
||||||
*
|
*
|
||||||
* Feed forward weight for position control in position control mode (EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
* Feed forward weight for position control in position control mode (POSHOLD). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
||||||
*
|
*
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
* @max 1.0
|
* @max 1.0
|
||||||
|
@ -176,7 +176,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
|
||||||
/**
|
/**
|
||||||
* Maximum tilt angle in air
|
* Maximum tilt angle in air
|
||||||
*
|
*
|
||||||
* Limits maximum tilt in AUTO and EASY modes during flight.
|
* Limits maximum tilt in AUTO and POSHOLD modes during flight.
|
||||||
*
|
*
|
||||||
* @unit deg
|
* @unit deg
|
||||||
* @min 0.0
|
* @min 0.0
|
||||||
|
|
|
@ -35,8 +35,8 @@ void BlockSegwayController::update() {
|
||||||
|
|
||||||
// handle autopilot modes
|
// handle autopilot modes
|
||||||
if (_status.main_state == MAIN_STATE_AUTO ||
|
if (_status.main_state == MAIN_STATE_AUTO ||
|
||||||
_status.main_state == MAIN_STATE_SEATBELT ||
|
_status.main_state == MAIN_STATE_ALTHOLD ||
|
||||||
_status.main_state == MAIN_STATE_EASY) {
|
_status.main_state == MAIN_STATE_POSHOLD) {
|
||||||
_actuators.control[0] = spdCmd;
|
_actuators.control[0] = spdCmd;
|
||||||
_actuators.control[1] = spdCmd;
|
_actuators.control[1] = spdCmd;
|
||||||
|
|
||||||
|
|
|
@ -605,7 +605,7 @@ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
|
||||||
* @max 18
|
* @max 18
|
||||||
* @group Radio Calibration
|
* @group Radio Calibration
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(RC_MAP_EASY_SW, 0);
|
PARAM_DEFINE_INT32(RC_MAP_POSHLD_SW, 0);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Loiter switch channel mapping.
|
* Loiter switch channel mapping.
|
||||||
|
@ -703,7 +703,7 @@ PARAM_DEFINE_FLOAT(RC_ASSISTED_TH, 0.25f);
|
||||||
PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
|
PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Threshold for selecting easy mode
|
* Threshold for selecting poshold mode
|
||||||
*
|
*
|
||||||
* min:-1
|
* min:-1
|
||||||
* max:+1
|
* max:+1
|
||||||
|
@ -716,7 +716,7 @@ PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
|
||||||
* negative : true when channel<th
|
* negative : true when channel<th
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(RC_EASY_TH, 0.5f);
|
PARAM_DEFINE_FLOAT(RC_POSHOLD_TH, 0.5f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Threshold for selecting return to launch mode
|
* Threshold for selecting return to launch mode
|
||||||
|
|
|
@ -255,7 +255,7 @@ private:
|
||||||
|
|
||||||
int rc_map_mode_sw;
|
int rc_map_mode_sw;
|
||||||
int rc_map_return_sw;
|
int rc_map_return_sw;
|
||||||
int rc_map_easy_sw;
|
int rc_map_poshold_sw;
|
||||||
int rc_map_loiter_sw;
|
int rc_map_loiter_sw;
|
||||||
|
|
||||||
// int rc_map_offboard_ctrl_mode_sw;
|
// int rc_map_offboard_ctrl_mode_sw;
|
||||||
|
@ -271,12 +271,12 @@ private:
|
||||||
int32_t rc_fails_thr;
|
int32_t rc_fails_thr;
|
||||||
float rc_assisted_th;
|
float rc_assisted_th;
|
||||||
float rc_auto_th;
|
float rc_auto_th;
|
||||||
float rc_easy_th;
|
float rc_poshold_th;
|
||||||
float rc_return_th;
|
float rc_return_th;
|
||||||
float rc_loiter_th;
|
float rc_loiter_th;
|
||||||
bool rc_assisted_inv;
|
bool rc_assisted_inv;
|
||||||
bool rc_auto_inv;
|
bool rc_auto_inv;
|
||||||
bool rc_easy_inv;
|
bool rc_poshold_inv;
|
||||||
bool rc_return_inv;
|
bool rc_return_inv;
|
||||||
bool rc_loiter_inv;
|
bool rc_loiter_inv;
|
||||||
|
|
||||||
|
@ -309,7 +309,7 @@ private:
|
||||||
|
|
||||||
param_t rc_map_mode_sw;
|
param_t rc_map_mode_sw;
|
||||||
param_t rc_map_return_sw;
|
param_t rc_map_return_sw;
|
||||||
param_t rc_map_easy_sw;
|
param_t rc_map_poshold_sw;
|
||||||
param_t rc_map_loiter_sw;
|
param_t rc_map_loiter_sw;
|
||||||
|
|
||||||
// param_t rc_map_offboard_ctrl_mode_sw;
|
// param_t rc_map_offboard_ctrl_mode_sw;
|
||||||
|
@ -325,7 +325,7 @@ private:
|
||||||
param_t rc_fails_thr;
|
param_t rc_fails_thr;
|
||||||
param_t rc_assisted_th;
|
param_t rc_assisted_th;
|
||||||
param_t rc_auto_th;
|
param_t rc_auto_th;
|
||||||
param_t rc_easy_th;
|
param_t rc_poshold_th;
|
||||||
param_t rc_return_th;
|
param_t rc_return_th;
|
||||||
param_t rc_loiter_th;
|
param_t rc_loiter_th;
|
||||||
|
|
||||||
|
@ -526,7 +526,7 @@ Sensors::Sensors() :
|
||||||
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
|
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
|
||||||
|
|
||||||
/* optional mode switches, not mapped per default */
|
/* optional mode switches, not mapped per default */
|
||||||
_parameter_handles.rc_map_easy_sw = param_find("RC_MAP_EASY_SW");
|
_parameter_handles.rc_map_poshold_sw = param_find("RC_MAP_POSHLD_SW");
|
||||||
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
|
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
|
||||||
|
|
||||||
// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
|
// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
|
||||||
|
@ -541,7 +541,7 @@ Sensors::Sensors() :
|
||||||
_parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
|
_parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
|
||||||
_parameter_handles.rc_assisted_th = param_find("RC_ASSISTED_TH");
|
_parameter_handles.rc_assisted_th = param_find("RC_ASSISTED_TH");
|
||||||
_parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
|
_parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
|
||||||
_parameter_handles.rc_easy_th = param_find("RC_EASY_TH");
|
_parameter_handles.rc_poshold_th = param_find("RC_POSHOLD_TH");
|
||||||
_parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
|
_parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
|
||||||
_parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
|
_parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
|
||||||
|
|
||||||
|
@ -678,7 +678,7 @@ Sensors::parameters_update()
|
||||||
warnx("%s", paramerr);
|
warnx("%s", paramerr);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (param_get(_parameter_handles.rc_map_easy_sw, &(_parameters.rc_map_easy_sw)) != OK) {
|
if (param_get(_parameter_handles.rc_map_poshold_sw, &(_parameters.rc_map_poshold_sw)) != OK) {
|
||||||
warnx("%s", paramerr);
|
warnx("%s", paramerr);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -706,9 +706,9 @@ Sensors::parameters_update()
|
||||||
param_get(_parameter_handles.rc_auto_th, &(_parameters.rc_auto_th));
|
param_get(_parameter_handles.rc_auto_th, &(_parameters.rc_auto_th));
|
||||||
_parameters.rc_auto_inv = (_parameters.rc_auto_th<0);
|
_parameters.rc_auto_inv = (_parameters.rc_auto_th<0);
|
||||||
_parameters.rc_auto_th = fabs(_parameters.rc_auto_th);
|
_parameters.rc_auto_th = fabs(_parameters.rc_auto_th);
|
||||||
param_get(_parameter_handles.rc_easy_th, &(_parameters.rc_easy_th));
|
param_get(_parameter_handles.rc_poshold_th, &(_parameters.rc_poshold_th));
|
||||||
_parameters.rc_easy_inv = (_parameters.rc_easy_th<0);
|
_parameters.rc_poshold_inv = (_parameters.rc_poshold_th<0);
|
||||||
_parameters.rc_easy_th = fabs(_parameters.rc_easy_th);
|
_parameters.rc_poshold_th = fabs(_parameters.rc_poshold_th);
|
||||||
param_get(_parameter_handles.rc_return_th, &(_parameters.rc_return_th));
|
param_get(_parameter_handles.rc_return_th, &(_parameters.rc_return_th));
|
||||||
_parameters.rc_return_inv = (_parameters.rc_return_th<0);
|
_parameters.rc_return_inv = (_parameters.rc_return_th<0);
|
||||||
_parameters.rc_return_th = fabs(_parameters.rc_return_th);
|
_parameters.rc_return_th = fabs(_parameters.rc_return_th);
|
||||||
|
@ -724,7 +724,7 @@ Sensors::parameters_update()
|
||||||
|
|
||||||
_rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
|
_rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
|
||||||
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
|
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
|
||||||
_rc.function[EASY] = _parameters.rc_map_easy_sw - 1;
|
_rc.function[POSHOLD] = _parameters.rc_map_poshold_sw - 1;
|
||||||
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
|
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
|
||||||
|
|
||||||
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
|
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
|
||||||
|
@ -1478,7 +1478,7 @@ Sensors::rc_poll()
|
||||||
|
|
||||||
/* mode switches */
|
/* mode switches */
|
||||||
manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assisted_th, _parameters.rc_assisted_inv);
|
manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assisted_th, _parameters.rc_assisted_inv);
|
||||||
manual.easy_switch = get_rc_sw2pos_position(EASY, _parameters.rc_easy_th, _parameters.rc_easy_inv);
|
manual.poshold_switch = get_rc_sw2pos_position(POSHOLD, _parameters.rc_poshold_th, _parameters.rc_poshold_inv);
|
||||||
manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
|
manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
|
||||||
manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
|
manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
|
||||||
|
|
||||||
|
|
|
@ -77,8 +77,8 @@ struct manual_control_setpoint_s {
|
||||||
float aux5; /**< default function: payload drop */
|
float aux5; /**< default function: payload drop */
|
||||||
|
|
||||||
switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
|
switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
|
||||||
switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
|
switch_pos_t return_switch; /**< rturn to launch 2 position switch (mandatory): no effect, return */
|
||||||
switch_pos_t easy_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
|
switch_pos_t poshold_switch; /**< poshold 2 position switch (optional): althold, poshold */
|
||||||
switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
|
switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
|
||||||
}; /**< manual control inputs */
|
}; /**< manual control inputs */
|
||||||
|
|
||||||
|
|
|
@ -64,7 +64,7 @@ enum RC_CHANNELS_FUNCTION {
|
||||||
YAW = 3,
|
YAW = 3,
|
||||||
MODE = 4,
|
MODE = 4,
|
||||||
RETURN = 5,
|
RETURN = 5,
|
||||||
EASY = 6,
|
POSHOLD = 6,
|
||||||
LOITER = 7,
|
LOITER = 7,
|
||||||
OFFBOARD_MODE = 8,
|
OFFBOARD_MODE = 8,
|
||||||
FLAPS = 9,
|
FLAPS = 9,
|
||||||
|
|
|
@ -63,8 +63,8 @@
|
||||||
/* main state machine */
|
/* main state machine */
|
||||||
typedef enum {
|
typedef enum {
|
||||||
MAIN_STATE_MANUAL = 0,
|
MAIN_STATE_MANUAL = 0,
|
||||||
MAIN_STATE_SEATBELT,
|
MAIN_STATE_ALTHOLD,
|
||||||
MAIN_STATE_EASY,
|
MAIN_STATE_POSHOLD,
|
||||||
MAIN_STATE_AUTO,
|
MAIN_STATE_AUTO,
|
||||||
MAIN_STATE_MAX
|
MAIN_STATE_MAX
|
||||||
} main_state_t;
|
} main_state_t;
|
||||||
|
|
Loading…
Reference in New Issue