aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander')
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp66
-rw-r--r--src/modules/commander/airspeed_calibration.cpp6
-rw-r--r--src/modules/commander/commander.cpp367
-rw-r--r--src/modules/commander/commander_helper.cpp22
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp24
-rw-r--r--src/modules/commander/gyro_calibration.cpp18
-rw-r--r--src/modules/commander/mag_calibration.cpp47
-rw-r--r--src/modules/commander/module.mk4
-rw-r--r--src/modules/commander/px4_custom_mode.h5
-rw-r--r--src/modules/commander/rc_calibration.cpp6
-rw-r--r--src/modules/commander/state_machine_helper.cpp166
11 files changed, 442 insertions, 289 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 1cbdf9bf8..7180048ff 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -194,13 +194,13 @@ int do_accel_calibration(int mavlink_fd)
int32_t board_rotation_int;
param_get(board_rotation_h, &(board_rotation_int));
enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
- math::Matrix<3,3> board_rotation;
+ math::Matrix<3, 3> board_rotation;
get_rot_matrix(board_rotation_id, &board_rotation);
- math::Matrix<3,3> board_rotation_t = board_rotation.transposed();
+ math::Matrix<3, 3> board_rotation_t = board_rotation.transposed();
math::Vector<3> accel_offs_vec(&accel_offs[0]);
- math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec;
- math::Matrix<3,3> accel_T_mat(&accel_T[0][0]);
- math::Matrix<3,3> accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+ math::Vector<3> accel_offs_rotated = board_rotation_t *accel_offs_vec;
+ math::Matrix<3, 3> accel_T_mat(&accel_T[0][0]);
+ math::Matrix<3, 3> accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation;
accel_scale.x_offset = accel_offs_rotated(0);
accel_scale.x_scale = accel_T_rotated(0, 0);
@@ -277,11 +277,13 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
}
- if (old_done_count != done_count)
+ if (old_done_count != done_count) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
+ }
- if (done)
+ if (done) {
break;
+ }
mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
(!data_collected[0]) ? "x+ " : "",
@@ -380,11 +382,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
- if (d > still_thr2 * 8.0f)
+ if (d > still_thr2 * 8.0f) {
d = still_thr2 * 8.0f;
+ }
- if (d > accel_disp[i])
+ if (d > accel_disp[i]) {
accel_disp[i] = d;
+ }
}
/* still detector with hysteresis */
@@ -432,33 +436,39 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 0; // [ g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 0; // [ g, 0, 0 ]
+ }
if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 1; // [ -g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 1; // [ -g, 0, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 2; // [ 0, g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 2; // [ 0, g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 3; // [ 0, -g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 3; // [ 0, -g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
- return 4; // [ 0, 0, g ]
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr) {
+ return 4; // [ 0, 0, g ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
- return 5; // [ 0, 0, -g ]
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr) {
+ return 5; // [ 0, 0, -g ]
+ }
mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
@@ -485,8 +495,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
struct sensor_combined_s sensor;
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- for (int i = 0; i < 3; i++)
+ for (int i = 0; i < 3; i++) {
accel_sum[i] += sensor.accelerometer_m_s2[i];
+ }
count++;
@@ -495,8 +506,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
continue;
}
- if (errcount > samples_num / 10)
+ if (errcount > samples_num / 10) {
return ERROR;
+ }
}
for (int i = 0; i < 3; i++) {
@@ -512,8 +524,9 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0f)
- return ERROR; // Singular matrix
+ if (det == 0.0f) {
+ return ERROR; // Singular matrix
+ }
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
@@ -549,8 +562,9 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* calculate inverse matrix for A */
float mat_A_inv[3][3];
- if (mat_invert3(mat_A, mat_A_inv) != OK)
+ if (mat_invert3(mat_A, mat_A_inv) != OK) {
return ERROR;
+ }
/* copy results to accel_T */
for (int i = 0; i < 3; i++) {
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index c8c7a42e7..5d21d89d0 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -82,12 +82,15 @@ int do_airspeed_calibration(int mavlink_fd)
bool paramreset_successful = false;
int fd = open(AIRSPEED_DEVICE_PATH, 0);
+
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+
} else {
mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
+
close(fd);
}
@@ -112,8 +115,9 @@ int do_airspeed_calibration(int mavlink_fd)
diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 4f64b5c99..77d810a81 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -221,7 +221,7 @@ void print_status();
transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy);
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy);
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
@@ -233,8 +233,9 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
int commander_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
usage("missing command");
+ }
if (!strcmp(argv[1], "start")) {
@@ -248,7 +249,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 3000,
+ 2950,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -261,8 +262,9 @@ int commander_main(int argc, char *argv[])
if (!strcmp(argv[1], "stop")) {
- if (!thread_running)
+ if (!thread_running) {
errx(0, "commander already stopped");
+ }
thread_should_exit = true;
@@ -304,8 +306,9 @@ int commander_main(int argc, char *argv[])
void usage(const char *reason)
{
- if (reason)
+ if (reason) {
fprintf(stderr, "%s\n", reason);
+ }
fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
exit(1);
@@ -364,20 +367,22 @@ void print_status()
static orb_advert_t status_pub;
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy)
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy)
{
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
- // output appropriate error messages if the state cannot transition.
- arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
- if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
- mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
- } else if (arming_res == TRANSITION_DENIED) {
- tune_negative(true);
- }
-
- return arming_res;
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
+ // output appropriate error messages if the state cannot transition.
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
+
+ if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
+ mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
+
+ } else if (arming_res == TRANSITION_DENIED) {
+ tune_negative(true);
+ }
+
+ return arming_res;
}
bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
@@ -414,43 +419,61 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* set main state */
transition_result_t main_res = TRANSITION_DENIED;
- if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
- /* use autopilot-specific mode */
- if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (hil_ret == OK) {
+ ret = true;
+ }
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
- /* SEATBELT */
- main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ // Transition the arming state
+ arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ if (arming_res == TRANSITION_CHANGED) {
+ ret = true;
+ }
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
main_res = main_state_transition(status, MAIN_STATE_AUTO);
}
- } else {
- /* use base mode */
- if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
- /* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
+ /* ALTCTL */
+ main_res = main_state_transition(status, MAIN_STATE_ALTCTL);
- } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
- if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
+ /* ACRO */
+ main_res = main_state_transition(status, MAIN_STATE_ACRO);
+ }
- } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ } else {
+ /* use base mode */
+ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+ if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+
+ } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
}
}
}
+ if (main_res == TRANSITION_CHANGED) {
+ ret = true;
+ }
if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
@@ -463,24 +486,28 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
- // We use an float epsilon delta to test float equality.
- if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
+ // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
+ // We use an float epsilon delta to test float equality.
+ if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
- } else {
- // Flick to inair restore first if this comes from an onboard system
- if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
- status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
- }
- transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
- if (arming_res == TRANSITION_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- } else {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- }
- }
+ } else {
+
+ // Flick to inair restore first if this comes from an onboard system
+ if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
+ status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
+ }
+
+ transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
+
+ if (arming_res == TRANSITION_DENIED) {
+ mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ }
+ }
}
break;
@@ -504,7 +531,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
break;
- /* Flight termination */
+ /* Flight termination */
case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
//XXX: to enable the parachute, a param needs to be set
@@ -523,6 +550,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
case VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
+
if (use_current) {
/* use current position */
if (status->condition_global_position_valid) {
@@ -566,6 +594,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
break;
+
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
@@ -579,6 +608,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
+
if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, result);
@@ -612,9 +642,10 @@ int commander_thread_main(int argc, char *argv[])
char *main_states_str[MAIN_STATE_MAX];
main_states_str[0] = "MANUAL";
- main_states_str[1] = "SEATBELT";
- main_states_str[2] = "EASY";
+ main_states_str[1] = "ALTCTL";
+ main_states_str[2] = "POSCTL";
main_states_str[3] = "AUTO";
+ main_states_str[4] = "ACRO";
char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[0] = "INIT";
@@ -705,7 +736,7 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2900);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
@@ -860,6 +891,7 @@ int commander_thread_main(int argc, char *argv[])
/* re-check RC calibration */
rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
}
+
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
param_get(_param_enable_parachute, &parachute_enabled);
@@ -900,6 +932,7 @@ int commander_thread_main(int argc, char *argv[])
/* disarm if safety is now on and still armed */
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+
if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) {
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch");
}
@@ -925,9 +958,11 @@ int commander_thread_main(int argc, char *argv[])
/* update condition_global_position_valid */
/* hysteresis for EPH/EPV */
bool eph_epv_good;
+
if (status.condition_global_position_valid) {
if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) {
eph_epv_good = false;
+
} else {
eph_epv_good = true;
}
@@ -935,17 +970,19 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) {
eph_epv_good = true;
+
} else {
eph_epv_good = false;
}
}
+
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed);
/* check if GPS fix is ok */
/* update home position */
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
home.lat = global_position.lat;
home.lon = global_position.lon;
@@ -972,7 +1009,26 @@ int commander_thread_main(int argc, char *argv[])
}
/* update condition_local_position_valid and condition_local_altitude_valid */
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && eph_epv_good, &(status.condition_local_position_valid), &status_changed);
+ /* hysteresis for EPH */
+ bool local_eph_good;
+
+ if (status.condition_global_position_valid) {
+ if (local_position.eph > eph_epv_threshold * 2.0f) {
+ local_eph_good = false;
+
+ } else {
+ local_eph_good = true;
+ }
+
+ } else {
+ if (local_position.eph < eph_epv_threshold) {
+ local_eph_good = true;
+
+ } else {
+ local_eph_good = false;
+ }
+ }
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
if (status.condition_local_altitude_valid) {
@@ -1050,8 +1106,9 @@ int commander_thread_main(int argc, char *argv[])
/* compute system load */
uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
- if (last_idle_time > 0)
- status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ if (last_idle_time > 0) {
+ status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ }
last_idle_time = system_load.tasks[0].total_runtime;
@@ -1127,22 +1184,22 @@ int commander_thread_main(int argc, char *argv[])
status.rc_signal_lost = false;
- transition_result_t res; // store all transitions results here
+ transition_result_t arming_res; // store all transitions results here
/* arm/disarm by RC */
- res = TRANSITION_NOT_CHANGED;
+ arming_res = TRANSITION_NOT_CHANGED;
- /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm
+ /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSIST mode and landed) -> disarm
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
- sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ (status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
+ sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- res = arming_state_transition(&status, &safety, new_arming_state, &armed);
+ arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed);
stick_off_counter = 0;
} else {
@@ -1155,16 +1212,16 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position and we're in MANUAL mode -> arm */
if (status.arming_state == ARMING_STATE_STANDBY &&
- sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ sp_man.r > STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
+ print_reject_arm("#audio: NOT ARMING: Press safety switch first.");
} else if (status.main_state != MAIN_STATE_MANUAL) {
- print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+ print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
} else {
- res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
}
stick_on_counter = 0;
@@ -1177,7 +1234,7 @@ int commander_thread_main(int argc, char *argv[])
stick_on_counter = 0;
}
- if (res == TRANSITION_CHANGED) {
+ if (arming_res == TRANSITION_CHANGED) {
if (status.arming_state == ARMING_STATE_ARMED) {
mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
@@ -1185,24 +1242,24 @@ int commander_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
}
- } else if (res == TRANSITION_DENIED) {
+ } else if (arming_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied");
}
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* recover from failsafe */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
/* evaluate the main state machine according to mode switches */
- res = set_main_state_rc(&status, &sp_man);
+ transition_result_t main_res = set_main_state_rc(&status, &sp_man);
/* play tune on mode change only if armed, blink LED always */
- if (res == TRANSITION_CHANGED) {
+ if (main_res == TRANSITION_CHANGED) {
tune_positive(armed.armed);
- } else if (res == TRANSITION_DENIED) {
+ } else if (main_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: main state transition denied");
}
@@ -1215,7 +1272,8 @@ int commander_thread_main(int argc, char *argv[])
} else {
- /* MISSION switch */
+
+ /* LOITER switch */
if (sp_man.loiter_switch == SWITCH_POS_ON) {
/* stick is in LOITER position */
status.set_nav_state = NAVIGATION_STATE_LOITER;
@@ -1225,7 +1283,7 @@ int commander_thread_main(int argc, char *argv[])
status.set_nav_state = NAVIGATION_STATE_MISSION;
} else if ((sp_man.return_switch == SWITCH_POS_OFF || sp_man.return_switch == SWITCH_POS_MIDDLE) &&
- pos_sp_triplet.nav_state == NAV_STATE_RTL) {
+ pos_sp_triplet.nav_state == NAV_STATE_RTL) {
/* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
status.set_nav_state = NAVIGATION_STATE_MISSION;
}
@@ -1241,27 +1299,20 @@ int commander_thread_main(int argc, char *argv[])
if (armed.armed) {
if (status.main_state == MAIN_STATE_AUTO) {
/* check if AUTO mode still allowed */
- transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO);
+ transition_result_t auto_res = main_state_transition(&status, MAIN_STATE_AUTO);
- if (res == TRANSITION_NOT_CHANGED) {
+ if (auto_res == TRANSITION_NOT_CHANGED) {
last_auto_state_valid = hrt_absolute_time();
}
/* still invalid state after the timeout interval, execute failsafe */
- if ((hrt_elapsed_time(&last_auto_state_valid) > FAILSAFE_DEFAULT_TIMEOUT) && (res == TRANSITION_DENIED)) {
+ if ((hrt_elapsed_time(&last_auto_state_valid) > FAILSAFE_DEFAULT_TIMEOUT) && (auto_res == TRANSITION_DENIED)) {
/* AUTO mode denied, don't try RTL, switch to failsafe state LAND */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ auto_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_DENIED) {
+ if (auto_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
-
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: TERMINATION");
- }
-
- } else if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: LANDING");
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
} else {
status.set_nav_state = NAVIGATION_STATE_MISSION;
@@ -1269,47 +1320,37 @@ int commander_thread_main(int argc, char *argv[])
} else {
/* failsafe for manual modes */
- transition_result_t res = TRANSITION_DENIED;
+ transition_result_t manual_res = TRANSITION_DENIED;
if (!status.condition_landed) {
/* vehicle is not landed, try to perform RTL */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
-
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: RETURN TO LAND");
- }
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
}
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* RTL not allowed (no global position estimate) or not wanted, try LAND */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: LANDING");
- }
-
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
- } else if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: TERMINATION");
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
} else {
status.set_nav_state = NAVIGATION_STATE_RTL;
- }
+ }
}
} else {
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* reset failsafe when disarmed */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
}
}
// TODO remove this hack
- /* flight termination in manual mode if assisted switch is on easy position */
- if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch == SWITCH_POS_ON) {
+ /* flight termination in manual mode if assist switch is on POSCTL position */
+ if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctl_switch == SWITCH_POS_ON) {
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
tune_positive(armed.armed);
}
@@ -1323,8 +1364,9 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub))
+ if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub)) {
status_changed = true;
+ }
}
/* check which state machines for changes, clear "changed" flag */
@@ -1341,7 +1383,7 @@ int commander_thread_main(int argc, char *argv[])
/* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
// TODO remove code duplication
home.lat = global_position.lat;
@@ -1353,7 +1395,7 @@ int commander_thread_main(int argc, char *argv[])
home.z = local_position.z;
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "#audio: home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
/* announce new home position */
if (home_pub > 0) {
@@ -1367,6 +1409,7 @@ int commander_thread_main(int argc, char *argv[])
status.condition_home_position_valid = true;
}
}
+
was_armed = armed.armed;
if (main_state_changed) {
@@ -1530,21 +1573,24 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
} else if (actuator_armed->ready_to_arm) {
/* ready to arm, blink at 1Hz */
- if (leds_counter % 20 == 0)
+ if (leds_counter % 20 == 0) {
led_toggle(LED_BLUE);
+ }
} else {
/* not ready to arm, blink at 10Hz */
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_BLUE);
+ }
}
#endif
/* give system warnings on error LED, XXX maybe add memory usage warning too */
if (status->load > 0.95f) {
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_AMBER);
+ }
} else {
led_off(LED_AMBER);
@@ -1565,30 +1611,35 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_OFF: // MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (sp_man->acro_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_ACRO);
+
+ } else {
+ res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
// TRANSITION_DENIED is not possible here
break;
- case SWITCH_POS_MIDDLE: // ASSISTED
- if (sp_man->assisted_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_EASY);
+ case SWITCH_POS_MIDDLE: // ASSIST
+ if (sp_man->posctl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_POSCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT
- print_reject_mode(status, "EASY");
+ // else fallback to ALTCTL
+ print_reject_mode(status, "POSCTL");
}
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
- if (sp_man->assisted_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "SEATBELT");
+ if (sp_man->posctl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status, "ALTCTL");
}
// else fallback to MANUAL
@@ -1603,9 +1654,9 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT (EASY likely will not work too)
+ // else fallback to ALTCTL (POSCTL likely will not work too)
print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
@@ -1651,7 +1702,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ALTCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1662,7 +1713,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1675,6 +1726,18 @@ set_control_mode()
case MAIN_STATE_AUTO:
navigator_enabled = true;
+ break;
+
+ case MAIN_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
default:
break;
@@ -1758,7 +1821,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
- tune_positive(true);
+ tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
@@ -1772,7 +1835,8 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command);
+ /* this needs additional hints to the user - so let other messages pass and be spoken */
+ mavlink_log_critical(mavlink_fd, "command temporarily rejected: %u", cmd.command);
tune_negative(true);
break;
@@ -1808,8 +1872,9 @@ void *commander_low_prio_loop(void *arg)
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
/* timed out - periodic check for thread_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1824,8 +1889,9 @@ void *commander_low_prio_loop(void *arg)
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
- cmd.command == VEHICLE_CMD_DO_SET_SERVO)
+ cmd.command == VEHICLE_CMD_DO_SET_SERVO) {
continue;
+ }
/* only handle low-priority commands here */
switch (cmd.command) {
@@ -1903,6 +1969,7 @@ void *commander_low_prio_loop(void *arg)
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
@@ -1917,10 +1984,12 @@ void *commander_low_prio_loop(void *arg)
}
- if (calib_ret == OK)
+ if (calib_ret == OK) {
tune_positive(true);
- else
+
+ } else {
tune_negative(true);
+ }
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
@@ -1940,11 +2009,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters load ERROR");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1960,11 +2031,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters save error");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1974,8 +2047,8 @@ void *commander_low_prio_loop(void *arg)
}
case VEHICLE_CMD_START_RX_PAIR:
- /* handled in the IO driver */
- break;
+ /* handled in the IO driver */
+ break;
default:
/* don't answer on unsupported commands, it will be done in main loop */
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 0fd3c9e9e..940a04aa1 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -113,17 +113,22 @@ void buzzer_deinit()
close(buzzer);
}
-void set_tune(int tune) {
+void set_tune(int tune)
+{
unsigned int new_tune_duration = tune_durations[tune];
+
/* don't interrupt currently playing non-repeating tune by repeating */
if (tune_end == 0 || new_tune_duration != 0 || hrt_absolute_time() > tune_end) {
/* allow interrupting current non-repeating tune by the same tune */
if (tune != tune_current || new_tune_duration != 0) {
ioctl(buzzer, TONE_SET_ALARM, tune);
}
+
tune_current = tune;
+
if (new_tune_duration != 0) {
tune_end = hrt_absolute_time() + new_tune_duration;
+
} else {
tune_end = 0;
}
@@ -138,6 +143,7 @@ void tune_positive(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_GREEN);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_POSITIVE_TUNE);
}
@@ -151,6 +157,7 @@ void tune_neutral(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_WHITE);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEUTRAL_TUNE);
}
@@ -164,6 +171,7 @@ void tune_negative(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_RED);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEGATIVE_TUNE);
}
@@ -198,7 +206,7 @@ int led_init()
return ERROR;
}
- /* the blue LED is only available on FMUv1 but not FMUv2 */
+ /* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
(void)ioctl(leds, LED_ON, LED_BLUE);
/* we consider the amber led mandatory */
@@ -244,22 +252,25 @@ int led_off(int led)
void rgbled_set_color(rgbled_color_t color)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+ }
}
void rgbled_set_mode(rgbled_mode_t mode)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+ }
}
void rgbled_set_pattern(rgbled_pattern_t *pattern)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+ }
}
float battery_remaining_estimate_voltage(float voltage, float discharged)
@@ -299,6 +310,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged)
if (bat_capacity > 0.0f) {
/* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
+
} else {
/* else use voltage */
ret = remaining_voltage;
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 8a946543d..ee0d08391 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -317,34 +317,34 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to SEATBELT.
+ // MANUAL to ALTCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_SEATBELT;
- ut_assert("tranisition: manual to seatbelt",
+ new_main_state = MAIN_STATE_ALTCTL;
+ ut_assert("tranisition: manual to altctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
+ ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state);
- // MANUAL to SEATBELT, invalid local altitude.
+ // MANUAL to ALTCTRL, invalid local altitude.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = false;
- new_main_state = MAIN_STATE_SEATBELT;
+ new_main_state = MAIN_STATE_ALTCTL;
ut_assert("no transition: invalid local altitude",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to EASY.
+ // MANUAL to POSCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_EASY;
- ut_assert("transition: manual to easy",
+ new_main_state = MAIN_STATE_POSCTL;
+ ut_assert("transition: manual to posctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
+ ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state);
- // MANUAL to EASY, invalid local position.
+ // MANUAL to POSCTRL, invalid local position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = false;
- new_main_state = MAIN_STATE_EASY;
+ new_main_state = MAIN_STATE_POSCTL;
ut_assert("no transition: invalid position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 30cd0d48d..cbc2844c1 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -110,8 +110,9 @@ int do_gyro_calibration(int mavlink_fd)
gyro_scale.z_offset += gyro_report.z;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else {
poll_errcount++;
@@ -163,8 +164,9 @@ int do_gyro_calibration(int mavlink_fd)
/* apply new offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale)) {
warn("WARNING: failed to apply new offsets for gyro");
+ }
close(fd);
@@ -178,9 +180,9 @@ int do_gyro_calibration(int mavlink_fd)
float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+ if (mag_last > M_PI_F) { mag_last -= 2 * M_PI_F; }
- if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
+ if (mag_last < -M_PI_F) { mag_last += 2 * M_PI_F; }
uint64_t last_time = hrt_absolute_time();
@@ -220,15 +222,15 @@ int do_gyro_calibration(int mavlink_fd)
//float mag = -atan2f(magNav(1),magNav(0));
float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2 * M_PI_F;
+ if (mag > M_PI_F) { mag -= 2 * M_PI_F; }
- if (mag < -M_PI_F) mag += 2 * M_PI_F;
+ if (mag < -M_PI_F) { mag += 2 * M_PI_F; }
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2 * M_PI_F;
+ if (diff > M_PI_F) { diff -= 2 * M_PI_F; }
- if (diff < -M_PI_F) diff += 2 * M_PI_F;
+ if (diff < -M_PI_F) { diff += 2 * M_PI_F; }
baseline_integral += diff;
mag_last = mag;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 4ebf266f4..0ead22f77 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_interval = 45 * 1000 * 1000;
/* maximum 500 values */
- const unsigned int calibration_maxcount = 500;
+ const unsigned int calibration_maxcount = 240;
unsigned int calibration_counter;
struct mag_scale mscale_null = {
@@ -121,9 +121,24 @@ int do_mag_calibration(int mavlink_fd)
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+
+ /* clean up */
+ if (x != NULL) {
+ free(x);
+ }
+
+ if (y != NULL) {
+ free(y);
+ }
+
+ if (z != NULL) {
+ free(z);
+ }
+
res = ERROR;
return res;
}
+
} else {
/* exit */
return ERROR;
@@ -163,8 +178,9 @@ int do_mag_calibration(int mavlink_fd)
calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
+ if (calibration_counter % (calibration_maxcount / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ }
} else {
poll_errcount++;
@@ -198,14 +214,17 @@ int do_mag_calibration(int mavlink_fd)
}
}
- if (x != NULL)
+ if (x != NULL) {
free(x);
+ }
- if (y != NULL)
+ if (y != NULL) {
free(y);
+ }
- if (z != NULL)
+ if (z != NULL) {
free(z);
+ }
if (res == OK) {
/* apply calibration and set parameters */
@@ -234,23 +253,29 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
/* set parameters */
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
res = ERROR;
+ }
if (res != OK) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 554dfcb08..27ca5c182 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,3 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index 2144d3460..e0f8dc95d 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -12,9 +12,10 @@
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
- PX4_CUSTOM_MAIN_MODE_SEATBELT,
- PX4_CUSTOM_MAIN_MODE_EASY,
+ PX4_CUSTOM_MAIN_MODE_ALTCTL,
+ PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_ACRO,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 41f3ca0aa..0776894fb 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -69,11 +69,11 @@ int do_trim_calibration(int mavlink_fd)
orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
/* set parameters */
- float p = sp.roll;
+ float p = sp.y;
param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
+ p = sp.x;
param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
+ p = sp.r;
param_set(param_find("TRIM_YAW"), &p);
/* store to permanent storage */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 8dc616730..6f0e9794a 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -75,38 +75,38 @@ static bool failsafe_state_changed = true;
// though the transition is marked as true additional checks must be made. See arming_state_transition
// code for those checks.
static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
- // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
- { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
- { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
- { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
- { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
- { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
- { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
- { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
};
// You can index into the array with an arming_state_t in order to get it's textual representation
-static const char* state_names[ARMING_STATE_MAX] = {
- "ARMING_STATE_INIT",
- "ARMING_STATE_STANDBY",
- "ARMING_STATE_ARMED",
- "ARMING_STATE_ARMED_ERROR",
- "ARMING_STATE_STANDBY_ERROR",
- "ARMING_STATE_REBOOT",
- "ARMING_STATE_IN_AIR_RESTORE",
+static const char *state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
};
transition_result_t
arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
- const struct safety_s *safety, /// current safety settings
- arming_state_t new_arming_state, /// arming state requested
- struct actuator_armed_s *armed, /// current armed status
- const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
- // Double check that our static arrays are still valid
- ASSERT(ARMING_STATE_INIT == 0);
- ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
-
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
+
/*
* Perform an atomic state update
*/
@@ -117,63 +117,70 @@ arming_state_transition(struct vehicle_status_s *status, /// current
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == status->arming_state) {
ret = TRANSITION_NOT_CHANGED;
+
} else {
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
+
} else {
armed->lockdown = false;
}
-
- // Check that we have a valid state transition
- bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
- if (valid_transition) {
- // We have a good transition. Now perform any secondary validation.
- if (new_arming_state == ARMING_STATE_ARMED) {
- // Fail transition if we need safety switch press
- // Allow if coming from in air restore
- // Allow if HIL_STATE_ON
- if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first.");
- }
- valid_transition = false;
- }
- } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
- new_arming_state = ARMING_STATE_STANDBY_ERROR;
- }
- }
-
- // HIL can always go to standby
- if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
- valid_transition = true;
- }
-
- /* Sensors need to be initialized for STANDBY state */
- if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
- valid_transition = false;
- }
-
- // Finish up the state transition
- if (valid_transition) {
- armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
- armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
- ret = TRANSITION_CHANGED;
- status->arming_state = new_arming_state;
- arming_state_changed = true;
- }
- }
-
+
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
+
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ // Fail transition if we need safety switch press
+ // Allow if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch first.");
+ }
+
+ valid_transition = false;
+ }
+
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
+ }
+ }
+
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
+
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
+ }
+
+ // Finish up the state transition
+ if (valid_transition) {
+ armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
+ armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
+ ret = TRANSITION_CHANGED;
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
/* end of atomic state update */
irqrestore(flags);
- if (ret == TRANSITION_DENIED) {
- static const char* errMsg = "Invalid arming transition from %s to %s";
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
- warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "Invalid arming transition from %s to %s";
+
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
+
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
@@ -215,7 +222,11 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_ALTCTL:
/* need at minimum altitude estimate */
if (!status->is_rotary_wing ||
@@ -226,7 +237,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
@@ -301,7 +312,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
case HIL_STATE_OFF:
/* we're in HIL and unexpected things can happen if we disable HIL now */
- mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
+ mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
valid_transition = false;
break;
@@ -320,6 +331,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
/* list directory */
DIR *d;
d = opendir("/dev");
+
if (d) {
struct dirent *direntry;
@@ -331,26 +343,32 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
if (!strncmp("tty", direntry->d_name, 3)) {
continue;
}
+
/* skip mtd devices */
if (!strncmp("mtd", direntry->d_name, 3)) {
continue;
}
+
/* skip ram devices */
if (!strncmp("ram", direntry->d_name, 3)) {
continue;
}
+
/* skip MMC devices */
if (!strncmp("mmc", direntry->d_name, 3)) {
continue;
}
+
/* skip mavlink */
if (!strcmp("mavlink", direntry->d_name)) {
continue;
}
+
/* skip console */
if (!strcmp("console", direntry->d_name)) {
continue;
}
+
/* skip null */
if (!strcmp("null", direntry->d_name)) {
continue;