Function naming and remove unneeded sprintf

This commit is contained in:
Don Gagne 2014-03-17 11:01:15 -07:00
parent 4b980b508c
commit 783a240396
1 changed files with 7 additions and 9 deletions

View File

@ -219,7 +219,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 armDisarm(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.
@ -287,12 +287,12 @@ int commander_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "arm")) {
armDisarm(true, mavlink_fd, "command line");
arm_disarm(true, mavlink_fd, "command line");
exit(0);
}
if (!strcmp(argv[1], "2")) {
armDisarm(false, mavlink_fd, "command line");
arm_disarm(false, mavlink_fd, "command line");
exit(0);
}
@ -362,7 +362,7 @@ void print_status()
static orb_advert_t status_pub;
transition_result_t armDisarm(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;
@ -370,9 +370,7 @@ transition_result_t armDisarm(bool arm, const int mavlink_fd, const char* armedB
// 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) {
char buf[256];
snprintf(buf, sizeof(buf), "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
mavlink_log_info(mavlink_fd, buf);
mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
} else if (arming_res == TRANSITION_DENIED) {
tune_negative(true);
}
@ -416,7 +414,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
ret = true;
// Transition the arming state
arming_res = armDisarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
if (arming_res == TRANSITION_CHANGED)
ret = true;
@ -480,7 +478,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
return VEHICLE_CMD_RESULT_UNSUPPORTED;
}
transition_result_t arming_res = armDisarm(cmd->param1 == 1.0f, mavlink_fd, "arm/disarm component command");
transition_result_t arming_res = arm_disarm(cmd->param1 == 1.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;