aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorJohan Jansen <jnsn.johan@gmail.com>2015-01-16 16:46:16 +0100
committerJohan Jansen <jnsn.johan@gmail.com>2015-01-16 16:46:16 +0100
commit9ecadcd9b46ccf9bc58ea008b77f8408155c3665 (patch)
tree7e49cb1fa1c70927088bd8c8fb1256ff51f9b603 /src/modules
parenta581ae8ed60f0f08d4bf407aeeb0f3979b6ba38a (diff)
downloadpx4-firmware-9ecadcd9b46ccf9bc58ea008b77f8408155c3665.tar.gz
px4-firmware-9ecadcd9b46ccf9bc58ea008b77f8408155c3665.tar.bz2
px4-firmware-9ecadcd9b46ccf9bc58ea008b77f8408155c3665.zip
Astyle: Fix format for commander.cpp
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp50
1 files changed, 29 insertions, 21 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 57f94259c..aac6b2002 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -244,7 +244,8 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armed
* @brief This function initializes the home position of the vehicle. This happens first time we get a good GPS fix and each
* time the vehicle is armed with a good GPS fix.
**/
-static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home, const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition);
+static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home,
+ const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition);
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
@@ -566,7 +567,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
- /* Flight termination */
+ /* Flight termination */
case VEHICLE_CMD_DO_FLIGHTTERMINATION: {
if (cmd->param1 > 0.5f) {
//XXX update state machine?
@@ -726,15 +727,16 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
* @brief This function initializes the home position of the vehicle. This happens first time we get a good GPS fix and each
* time the vehicle is armed with a good GPS fix.
**/
-static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home, const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition)
+static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home,
+ const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition)
{
//Need global position fix to be able to set home
- if(!status.condition_global_position_valid) {
+ if (!status.condition_global_position_valid) {
return;
}
//Ensure that the GPS accuracy is good enough for intializing home
- if(globalPosition.eph > eph_threshold || globalPosition.epv > epv_threshold) {
+ if (globalPosition.eph > eph_threshold || globalPosition.epv > epv_threshold) {
return;
}
@@ -760,7 +762,7 @@ static void commander_set_home_position(orb_advert_t &homePub, home_position_s &
}
//Play tune first time we initialize HOME
- if(!status.condition_home_position_valid) {
+ if (!status.condition_home_position_valid) {
tune_positive(true);
}
@@ -1147,8 +1149,8 @@ int commander_thread_main(int argc, char *argv[])
}
/* set vehicle_status.is_vtol flag */
- status.is_vtol = (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) ||
- (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
+ status.is_vtol = (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) ||
+ (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
/* check and update system / component ID */
param_get(_param_system_id, &(status.system_id));
@@ -1310,12 +1312,12 @@ int commander_thread_main(int argc, char *argv[])
}
//Notify the user if the status of the safety switch changes
- if(safety.safety_switch_available && previous_safety_off != safety.safety_off) {
+ if (safety.safety_switch_available && previous_safety_off != safety.safety_off) {
- if(safety.safety_off) {
+ if (safety.safety_off) {
set_tune(TONE_NOTIFY_POSITIVE_TUNE);
- }
- else {
+
+ } else {
tune_neutral(true);
}
@@ -1330,6 +1332,7 @@ int commander_thread_main(int argc, char *argv[])
/* vtol status changed */
orb_copy(ORB_ID(vtol_vehicle_status), vtol_vehicle_status_sub, &vtol_status);
status.vtol_fw_permanent_stab = vtol_status.fw_permanent_stab;
+
/* Make sure that this is only adjusted if vehicle realy is of type vtol*/
if (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR || VEHICLE_TYPE_VTOL_QUADROTOR) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
@@ -1632,7 +1635,8 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",(hrt_absolute_time()-status.rc_signal_lost_timestamp)/1000);
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",
+ (hrt_absolute_time() - status.rc_signal_lost_timestamp) / 1000);
status_changed = true;
}
}
@@ -1733,9 +1737,9 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (!status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)",hrt_absolute_time()/1000);
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)", hrt_absolute_time() / 1000);
status.rc_signal_lost = true;
- status.rc_signal_lost_timestamp=sp_man.timestamp;
+ status.rc_signal_lost_timestamp = sp_man.timestamp;
status_changed = true;
}
}
@@ -1886,13 +1890,13 @@ int commander_thread_main(int argc, char *argv[])
const hrt_abstime now = hrt_absolute_time();
//First time home position update
- if(!status.condition_home_position_valid) {
- commander_set_home_position(home_pub, home, local_position, global_position);
+ if (!status.condition_home_position_valid) {
+ commander_set_home_position(home_pub, home, local_position, global_position);
}
/* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
- else if(arming_state_changed && armed.armed && !was_armed && now > commander_boot_timestamp + 2000000) {
- commander_set_home_position(home_pub, home, local_position, global_position);
+ else if (arming_state_changed && armed.armed && !was_armed && now > commander_boot_timestamp + 2000000) {
+ commander_set_home_position(home_pub, home, local_position, global_position);
}
/* print new state */
@@ -1919,11 +1923,14 @@ int commander_thread_main(int argc, char *argv[])
if (status.failsafe != failsafe_old) {
status_changed = true;
+
if (status.failsafe) {
mavlink_log_critical(mavlink_fd, "failsafe mode on");
+
} else {
mavlink_log_critical(mavlink_fd, "failsafe mode off");
}
+
failsafe_old = status.failsafe;
}
@@ -1969,7 +1976,7 @@ int commander_thread_main(int argc, char *argv[])
if (!armed.armed || (safety.safety_switch_available && !safety.safety_off)) {
//Notify the user that it is safe to approach the vehicle
- if(arm_tune_played) {
+ if (arm_tune_played) {
tune_neutral(true);
}
@@ -2436,6 +2443,7 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
}
+
break;
default:
@@ -2474,7 +2482,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: