Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adapted acceptance radius for rovers, and added vehicle_type field #11918

Merged
merged 6 commits into from
Jun 13, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/1060_rover
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# @name Rover
#

sh /etc/init.d/rc.ugv_defaults
sh /etc/init.d/rc.rover_defaults

if [ $AUTOCNF = yes ]
then
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ fi

# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps.
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
sh etc/init.d/rc.vehicle_setup

Expand Down
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ px4_add_romfs_files(
rcS
rc.sensors
rc.thermal_cal
rc.ugv_apps
rc.ugv_defaults
rc.rover_apps
rc.rover_defaults
rc.vehicle_setup
rc.vtol_apps
rc.vtol_defaults
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
# @board px4_fmu-v2 exclude
#

sh /etc/init.d/rc.ugv_defaults
sh /etc/init.d/rc.rover_defaults

if [ $AUTOCNF = yes ]
then
Expand Down Expand Up @@ -54,10 +54,10 @@ then
param set PWM_MIN 1000
fi

# Configure this as ugv
# Configure this as rover
set MAV_TYPE 10

# Set mixer
set MIXER ugv_generic
set MIXER rover_generic

set PWM_MAIN_REV2 1
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
# @board px4_fmu-v2 exclude
#

sh /etc/init.d/rc.ugv_defaults
sh /etc/init.d/rc.rover_defaults

#
# This section can be enabled once tuning parameters for this particular
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
# @board px4_fmu-v2 exclude
#

sh /etc/init.d/rc.ugv_defaults
sh /etc/init.d/rc.rover_defaults

if [ $AUTOCNF = yes ]
then
Expand Down Expand Up @@ -56,7 +56,7 @@ then
param set PWM_MIN 1000
fi

# Configure this as ugv
# Configure this as rover
set MAV_TYPE 10

# Set mixer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,4 +23,4 @@ gnd_pos_control start
#
# Start Land Detector.
#
land_detector start ugv
land_detector start rover
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#

set VEHICLE_TYPE ugv
set VEHICLE_TYPE rover

if [ $AUTOCNF = yes ]
then
Expand Down
6 changes: 3 additions & 3 deletions ROMFS/px4fmu_common/init.d/rc.vehicle_setup
Original file line number Diff line number Diff line change
Expand Up @@ -87,12 +87,12 @@ fi
#
# UGV setup.
#
if [ $VEHICLE_TYPE = ugv ]
if [ $VEHICLE_TYPE = rover ]
then
if [ $MIXER = none ]
then
# Set default mixer for UGV if not defined.
set MIXER ugv_generic
set MIXER rover_generic
fi

if [ $MAV_TYPE = none ]
Expand All @@ -108,7 +108,7 @@ then
sh /etc/init.d/rc.interface

# Start standard UGV apps.
sh /etc/init.d/rc.ugv_apps
sh /etc/init.d/rc.rover_apps
fi

#
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -421,7 +421,7 @@ else
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps.
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
sh /etc/init.d/rc.vehicle_setup

Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/mixers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ px4_add_romfs_files(
stampede.main.mix
tri_y_yaw-.main.mix
tri_y_yaw+.main.mix
ugv_generic.main.mix
rover_generic.main.mix
Viper.main.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_test/mixers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ px4_add_romfs_files(
quad_+.main.mix
quad_test.mix
quad_+_vtol.main.mix
ugv_generic.main.mix
rover_generic.main.mix
vtol1_test.mix
vtol2_test.mix
vtol_AAERT.aux.mix
Expand Down
9 changes: 8 additions & 1 deletion msg/vehicle_status.msg
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,11 @@ uint8 RC_IN_MODE_DEFAULT = 0
uint8 RC_IN_MODE_OFF = 1
uint8 RC_IN_MODE_GENERATED = 2

uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3

# state machine / state of vehicle.
# Encodes the complete system state and is set by the commander app.

Expand All @@ -61,7 +66,9 @@ uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field

bool is_rotary_wing # True if system is in rotary wing configuration, so for a VTOL this is only true while flying as a multicopter
uint8 vehicle_type # Type of vehicle (fixed-wing, rotary wing, ground)
# If the vehicle is a VTOL, then this value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter,
# and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing

bool is_vtol # True if the system is VTOL capable
bool vtol_fw_permanent_stab # True if VTOL should stabilize attitude for fw in manual mode
Expand Down
3 changes: 2 additions & 1 deletion src/lib/FlightTasks/tasks/Auto/FlightTaskAuto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,8 @@ bool FlightTaskAuto::_evaluateTriplets()
_mission_gear = _sub_triplet_setpoint->get().current.landing_gear;
}

if (_param_com_obs_avoid.get() && _sub_vehicle_status->get().is_rotary_wing) {
if (_param_com_obs_avoid.get()
&& _sub_vehicle_status->get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
_obstacle_avoidance.updateAvoidanceDesiredWaypoints(_triplet_target, _yaw_setpoint, _yawspeed_setpoint,
_triplet_next_wp,
_sub_triplet_setpoint->get().next.yaw,
Expand Down
73 changes: 53 additions & 20 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,7 +431,8 @@ int commander_main(int argc, char *argv[])
if (!strcmp(argv[1], "transition")) {

bool ret = send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_VTOL_TRANSITION,
(float)(status.is_rotary_wing ? vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW :
(float)(status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING ?
vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW :
vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC));

return (ret ? 0 : 1);
Expand Down Expand Up @@ -1288,7 +1289,20 @@ Commander::run()
int32_t system_type;
param_get(_param_sys_type, &system_type); // get system type
status.system_type = (uint8_t)system_type;
status.is_rotary_wing = is_rotary_wing(&status) || is_vtol(&status);

if (is_rotary_wing(&status) || is_vtol(&status)) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;

} else if (is_fixed_wing(&status)) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;

} else if (is_ground_rover(&status)) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;

} else {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_UNKNOWN;
}

status.is_vtol = is_vtol(&status);

commander_boot_timestamp = hrt_absolute_time();
Expand Down Expand Up @@ -1393,12 +1407,19 @@ Commander::run()
status.system_type = (uint8_t)system_type;
}

const bool is_rotary = is_rotary_wing(&status) || (is_vtol(&status) && vtol_status.vtol_in_rw_mode);
const bool is_fixed = is_fixed_wing(&status) || (is_vtol(&status) && !vtol_status.vtol_in_rw_mode);
const bool is_ground = is_ground_rover(&status);

/* disable manual override for all systems that rely on electronic stabilization */
if (is_rotary_wing(&status) || (is_vtol(&status) && vtol_status.vtol_in_rw_mode)) {
status.is_rotary_wing = true;
if (is_rotary) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;

} else {
status.is_rotary_wing = false;
} else if (is_fixed) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;

} else if (is_ground) {
status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;
}

/* set vehicle_status.is_vtol flag */
Expand Down Expand Up @@ -1607,8 +1628,14 @@ Commander::run()
if (is_vtol(&status)) {

// Check if there has been any change while updating the flags
if (status.is_rotary_wing != vtol_status.vtol_in_rw_mode) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
const auto new_vehicle_type = vtol_status.vtol_in_rw_mode ?
vehicle_status_s::VEHICLE_TYPE_ROTARY_WING :
vehicle_status_s::VEHICLE_TYPE_FIXED_WING;

if (new_vehicle_type != status.vehicle_type) {
status.vehicle_type = vtol_status.vtol_in_rw_mode ?
vehicle_status_s::VEHICLE_TYPE_ROTARY_WING :
vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
status_changed = true;
}

Expand All @@ -1627,8 +1654,10 @@ Commander::run()
status_changed = true;
}

if (armed.soft_stop != !status.is_rotary_wing) {
armed.soft_stop = !status.is_rotary_wing;
const bool should_soft_stop = (status.vehicle_type != vehicle_status_s::VEHICLE_TYPE_ROTARY_WING);

if (armed.soft_stop != should_soft_stop) {
armed.soft_stop = should_soft_stop;
status_changed = true;
}
}
Expand Down Expand Up @@ -1975,7 +2004,7 @@ Commander::run()

if (in_armed_state &&
status.rc_input_mode != vehicle_status_s::RC_IN_MODE_OFF &&
(status.is_rotary_wing || (!status.is_rotary_wing && land_detector.landed)) &&
(status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING || land_detector.landed) &&
(stick_in_lower_left || arm_button_pressed || arm_switch_to_disarm_transition)) {

if (internal_state.main_state != commander_state_s::MAIN_STATE_MANUAL &&
Expand Down Expand Up @@ -2123,7 +2152,7 @@ Commander::run()
* only for fixed wing for now
*/
if (!status_flags.circuit_breaker_engaged_enginefailure_check &&
!status.is_rotary_wing && !status.is_vtol && armed.armed) {
status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && !status.is_vtol && armed.armed) {

actuator_controls_s actuator_controls = {};
actuator_controls_sub.copy(&actuator_controls);
Expand Down Expand Up @@ -2910,10 +2939,10 @@ Commander::set_main_state_rc(const vehicle_status_s &status_local, bool *changed
/* manual mode is stabilized already for multirotors, so switch to acro
* for any non-manual mode
*/
if (status.is_rotary_wing && !status.is_vtol) {
if (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !status.is_vtol) {
res = main_state_transition(status_local, commander_state_s::MAIN_STATE_ACRO, status_flags, &internal_state);

} else if (!status.is_rotary_wing) {
} else if (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
res = main_state_transition(status_local, commander_state_s::MAIN_STATE_STAB, status_flags, &internal_state);

} else {
Expand All @@ -2923,7 +2952,7 @@ Commander::set_main_state_rc(const vehicle_status_s &status_local, bool *changed
} else if (sp_man.rattitude_switch == manual_control_setpoint_s::SWITCH_POS_ON) {
/* Similar to acro transitions for multirotors. FW aircraft don't need a
* rattitude mode.*/
if (status.is_rotary_wing) {
if (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
res = main_state_transition(status_local, commander_state_s::MAIN_STATE_RATTITUDE, status_flags, &internal_state);

} else {
Expand Down Expand Up @@ -3119,7 +3148,8 @@ set_control_mode()
{
/* set vehicle_control_mode according to set_navigation_state */
control_mode.flag_armed = armed.armed;
control_mode.flag_external_manual_override_ok = (!status.is_rotary_wing && !status.is_vtol);
control_mode.flag_external_manual_override_ok = (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING
&& !status.is_vtol);
control_mode.flag_control_offboard_enabled = false;

switch (status.nav_state) {
Expand Down Expand Up @@ -3350,10 +3380,11 @@ set_control_mode()
bool
stabilization_required()
{
return (status.is_rotary_wing || // is a rotary wing, or
return (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING || // is a rotary wing, or
status.vtol_fw_permanent_stab || // is a VTOL in fixed wing mode and stabilisation is on, or
(vtol_status.vtol_in_trans_mode && // is currently a VTOL transitioning AND
!status.is_rotary_wing)); // is a fixed wing, ie: transitioning back to rotary wing mode
status.vehicle_type ==
vehicle_status_s::VEHICLE_TYPE_FIXED_WING)); // is a fixed wing, ie: transitioning back to rotary wing mode
}

void
Expand Down Expand Up @@ -4020,9 +4051,11 @@ void Commander::airspeed_use_check()
_sensor_bias_sub.update();
const sensor_bias_s &sensors = _sensor_bias_sub.get();

bool is_fixed_wing = status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING;

// assume airspeed sensor is good before starting FW flight
bool valid_flight_condition = (status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) &&
!status.is_rotary_wing && !land_detector.landed;
is_fixed_wing && !land_detector.landed;
bool fault_declared = false;
bool fault_cleared = false;
bool bad_number_fail = !PX4_ISFINITE(airspeed.indicated_airspeed_m_s) || !PX4_ISFINITE(airspeed.true_airspeed_m_s);
Expand Down Expand Up @@ -4318,7 +4351,7 @@ void Commander::estimator_check(bool *status_changed)
* for a short time interval after takeoff. Fixed wing vehicles can recover using GPS heading,
* but rotary wing vehicles cannot so the position and velocity validity needs to be latched
* to false after failure to prevent flyaway crashes */
if (run_quality_checks && status.is_rotary_wing) {
if (run_quality_checks && status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {

if (status.arming_state == vehicle_status_s::ARMING_STATE_STANDBY) {
// reset flags and timer
Expand Down
5 changes: 3 additions & 2 deletions src/modules/commander/PreflightCheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -727,7 +727,8 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status,

/* Perform airspeed check only if circuit breaker is not
* engaged and it's not a rotary wing */
if (!status_flags.circuit_breaker_engaged_airspd_check && (!status.is_rotary_wing || status.is_vtol)) {
if (!status_flags.circuit_breaker_engaged_airspd_check &&
(status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING || status.is_vtol)) {
checkAirspeed = true;
}

Expand Down Expand Up @@ -960,7 +961,7 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status,
// only check EKF2 data if EKF2 is selected as the estimator and GNSS checking is enabled
int32_t estimator_type = -1;

if (status.is_rotary_wing && !status.is_vtol) {
if (status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !status.is_vtol) {
param_get(param_find("SYS_MC_EST_GROUP"), &estimator_type);

} else {
Expand Down
12 changes: 12 additions & 0 deletions src/modules/commander/commander_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,11 @@

using namespace DriverFramework;

#define VEHICLE_TYPE_FIXED_WING 1
#define VEHICLE_TYPE_QUADROTOR 2
#define VEHICLE_TYPE_COAXIAL 3
#define VEHICLE_TYPE_HELICOPTER 4
#define VEHICLE_TYPE_GROUND_ROVER 10
#define VEHICLE_TYPE_HEXAROTOR 13
#define VEHICLE_TYPE_OCTOROTOR 14
#define VEHICLE_TYPE_TRICOPTER 15
Expand Down Expand Up @@ -108,6 +110,16 @@ bool is_vtol(const struct vehicle_status_s *current_status)
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED5);
}

bool is_fixed_wing(const struct vehicle_status_s *current_status)
{
return current_status->system_type == VEHICLE_TYPE_FIXED_WING;
}

bool is_ground_rover(const struct vehicle_status_s *current_status)
{
return current_status->system_type == VEHICLE_TYPE_GROUND_ROVER;
}

static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message
static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence
static int tune_current = TONE_STOP_TUNE; // currently playing tune, can be interrupted after tune_end
Expand Down
Loading