Plane: Change from printf statement to print, println statement.
This commit is contained in:
parent
8f80aa9c94
commit
0ee8edc29d
@ -70,11 +70,11 @@ int8_t Plane::dump_log(uint8_t argc, const Menu::arg *argv)
|
|||||||
DataFlash.DumpPageInfo(cliSerial);
|
DataFlash.DumpPageInfo(cliSerial);
|
||||||
return(-1);
|
return(-1);
|
||||||
} else if (dump_log_num <= 0) {
|
} else if (dump_log_num <= 0) {
|
||||||
cliSerial->printf("dumping all\n");
|
cliSerial->println("dumping all");
|
||||||
Log_Read(0, 1, 0);
|
Log_Read(0, 1, 0);
|
||||||
return(-1);
|
return(-1);
|
||||||
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
||||||
cliSerial->printf("bad log number\n");
|
cliSerial->println("bad log number");
|
||||||
return(-1);
|
return(-1);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -96,7 +96,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
uint32_t bits;
|
uint32_t bits;
|
||||||
|
|
||||||
if (argc != 2) {
|
if (argc != 2) {
|
||||||
cliSerial->printf("missing log type\n");
|
cliSerial->println("missing log type");
|
||||||
return(-1);
|
return(-1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1456,14 +1456,14 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
|||||||
void Plane::load_parameters(void)
|
void Plane::load_parameters(void)
|
||||||
{
|
{
|
||||||
if (!AP_Param::check_var_info()) {
|
if (!AP_Param::check_var_info()) {
|
||||||
cliSerial->printf("Bad parameter table\n");
|
cliSerial->println("Bad parameter table");
|
||||||
AP_HAL::panic("Bad parameter table");
|
AP_HAL::panic("Bad parameter table");
|
||||||
}
|
}
|
||||||
if (!g.format_version.load() ||
|
if (!g.format_version.load() ||
|
||||||
g.format_version != Parameters::k_format_version) {
|
g.format_version != Parameters::k_format_version) {
|
||||||
|
|
||||||
// erase all parameters
|
// erase all parameters
|
||||||
cliSerial->printf("Firmware change: erasing EEPROM...\n");
|
cliSerial->println("Firmware change: erasing EEPROM...");
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
|
||||||
// save the current format version
|
// save the current format version
|
||||||
|
@ -246,7 +246,7 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
|
|
||||||
fileSize = create_mixer(buf, buf_size, mixer_filename);
|
fileSize = create_mixer(buf, buf_size, mixer_filename);
|
||||||
if (!fileSize) {
|
if (!fileSize) {
|
||||||
hal.console->printf("Unable to create mixer\n");
|
hal.console->println("Unable to create mixer");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -280,13 +280,13 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
/* reset any existing mixer in px4io. This shouldn't be needed,
|
/* reset any existing mixer in px4io. This shouldn't be needed,
|
||||||
* but is good practice */
|
* but is good practice */
|
||||||
if (ioctl(px4io_fd, MIXERIOCRESET, 0) != 0) {
|
if (ioctl(px4io_fd, MIXERIOCRESET, 0) != 0) {
|
||||||
hal.console->printf("Unable to reset mixer\n");
|
hal.console->println("Unable to reset mixer");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* pass the buffer to the device */
|
/* pass the buffer to the device */
|
||||||
if (ioctl(px4io_fd, MIXERIOCLOADBUF, (unsigned long)buf) != 0) {
|
if (ioctl(px4io_fd, MIXERIOCLOADBUF, (unsigned long)buf) != 0) {
|
||||||
hal.console->printf("Unable to send mixer to IO\n");
|
hal.console->println("Unable to send mixer to IO");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -348,7 +348,7 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (ioctl(px4io_fd, PWM_SERVO_SET_RC_CONFIG, (unsigned long)&config) != 0) {
|
if (ioctl(px4io_fd, PWM_SERVO_SET_RC_CONFIG, (unsigned long)&config) != 0) {
|
||||||
hal.console->printf("SET_RC_CONFIG failed\n");
|
hal.console->println("SET_RC_CONFIG failed");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -362,7 +362,7 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (ioctl(px4io_fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values) != 0) {
|
if (ioctl(px4io_fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values) != 0) {
|
||||||
hal.console->printf("SET_MIN_PWM failed\n");
|
hal.console->println("SET_MIN_PWM failed");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -376,16 +376,16 @@ bool Plane::setup_failsafe_mixing(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (ioctl(px4io_fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values) != 0) {
|
if (ioctl(px4io_fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values) != 0) {
|
||||||
hal.console->printf("SET_MAX_PWM failed\n");
|
hal.console->println("SET_MAX_PWM failed");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
|
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
|
||||||
hal.console->printf("SET_OVERRIDE_OK failed\n");
|
hal.console->println("SET_OVERRIDE_OK failed");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 1) != 0) {
|
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 1) != 0) {
|
||||||
hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
|
hal.console->println("SET_OVERRIDE_IMMEDIATE failed");
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -73,7 +73,7 @@ void Plane::zero_eeprom(void)
|
|||||||
{
|
{
|
||||||
cliSerial->printf("\nErasing EEPROM\n");
|
cliSerial->printf("\nErasing EEPROM\n");
|
||||||
StorageManager::erase();
|
StorageManager::erase();
|
||||||
cliSerial->printf("done\n");
|
cliSerial->println("done");
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
|
@ -152,7 +152,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
oldSwitchPosition = readSwitch();
|
oldSwitchPosition = readSwitch();
|
||||||
|
|
||||||
cliSerial->printf("Unplug battery, throttle in neutral, turn off radio.\n");
|
cliSerial->println("Unplug battery, throttle in neutral, turn off radio.");
|
||||||
while(channel_throttle->get_control_in() > 0) {
|
while(channel_throttle->get_control_in() > 0) {
|
||||||
hal.scheduler->delay(20);
|
hal.scheduler->delay(20);
|
||||||
read_radio();
|
read_radio();
|
||||||
@ -168,7 +168,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if(oldSwitchPosition != readSwitch()) {
|
if(oldSwitchPosition != readSwitch()) {
|
||||||
cliSerial->printf("CONTROL MODE CHANGED: ");
|
cliSerial->print("CONTROL MODE CHANGED: ");
|
||||||
print_flight_mode(cliSerial, readSwitch());
|
print_flight_mode(cliSerial, readSwitch());
|
||||||
cliSerial->println();
|
cliSerial->println();
|
||||||
fail_test++;
|
fail_test++;
|
||||||
@ -185,7 +185,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
if(cliSerial->available() > 0) {
|
if(cliSerial->available() > 0) {
|
||||||
cliSerial->printf("LOS caused no change in APM.\n");
|
cliSerial->println("LOS caused no change in APM.");
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -197,14 +197,14 @@ int8_t Plane::test_relay(uint8_t argc, const Menu::arg *argv)
|
|||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
|
|
||||||
while(1) {
|
while(1) {
|
||||||
cliSerial->printf("Relay on\n");
|
cliSerial->println("Relay on");
|
||||||
relay.on(0);
|
relay.on(0);
|
||||||
hal.scheduler->delay(3000);
|
hal.scheduler->delay(3000);
|
||||||
if(cliSerial->available() > 0) {
|
if(cliSerial->available() > 0) {
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
|
|
||||||
cliSerial->printf("Relay off\n");
|
cliSerial->println("Relay off");
|
||||||
relay.off(0);
|
relay.off(0);
|
||||||
hal.scheduler->delay(3000);
|
hal.scheduler->delay(3000);
|
||||||
if(cliSerial->available() > 0) {
|
if(cliSerial->available() > 0) {
|
||||||
@ -219,7 +219,7 @@ int8_t Plane::test_wp(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
// save the alitude above home option
|
// save the alitude above home option
|
||||||
if (g.RTL_altitude_cm < 0) {
|
if (g.RTL_altitude_cm < 0) {
|
||||||
cliSerial->printf("Hold current altitude\n");
|
cliSerial->println("Hold current altitude");
|
||||||
}else{
|
}else{
|
||||||
cliSerial->printf("Hold altitude of %dm\n", (int)g.RTL_altitude_cm/100);
|
cliSerial->printf("Hold altitude of %dm\n", (int)g.RTL_altitude_cm/100);
|
||||||
}
|
}
|
||||||
@ -254,7 +254,7 @@ int8_t Plane::test_xbee(uint8_t argc, const Menu::arg *argv)
|
|||||||
{
|
{
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
cliSerial->printf("Begin XBee X-CTU Range and RSSI Test:\n");
|
cliSerial->println("Begin XBee X-CTU Range and RSSI Test:");
|
||||||
|
|
||||||
while(1) {
|
while(1) {
|
||||||
|
|
||||||
@ -273,7 +273,7 @@ int8_t Plane::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
|
|
||||||
cliSerial->printf("Control CH ");
|
cliSerial->print("Control CH ");
|
||||||
|
|
||||||
cliSerial->println(FLIGHT_MODE_CHANNEL, BASE_DEC);
|
cliSerial->println(FLIGHT_MODE_CHANNEL, BASE_DEC);
|
||||||
|
|
||||||
@ -333,7 +333,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
|
|||||||
(long)loc.alt/100,
|
(long)loc.alt/100,
|
||||||
(int)gps.num_sats());
|
(int)gps.num_sats());
|
||||||
} else {
|
} else {
|
||||||
cliSerial->printf(".");
|
cliSerial->print(".");
|
||||||
}
|
}
|
||||||
if(cliSerial->available() > 0) {
|
if(cliSerial->available() > 0) {
|
||||||
return (0);
|
return (0);
|
||||||
@ -343,7 +343,7 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
|
int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
//cliSerial->printf("Calibrating.");
|
//cliSerial->print("Calibrating.");
|
||||||
ahrs.init();
|
ahrs.init();
|
||||||
ahrs.set_fly_forward(true);
|
ahrs.set_fly_forward(true);
|
||||||
ahrs.set_wind_estimation(true);
|
ahrs.set_wind_estimation(true);
|
||||||
@ -394,7 +394,7 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||||||
int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
if (!g.compass_enabled) {
|
if (!g.compass_enabled) {
|
||||||
cliSerial->printf("Compass: ");
|
cliSerial->print("Compass: ");
|
||||||
print_enabled(false);
|
print_enabled(false);
|
||||||
return (0);
|
return (0);
|
||||||
}
|
}
|
||||||
@ -468,13 +468,13 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||||||
int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
|
int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
if (!airspeed.enabled()) {
|
if (!airspeed.enabled()) {
|
||||||
cliSerial->printf("airspeed: ");
|
cliSerial->print("airspeed: ");
|
||||||
print_enabled(false);
|
print_enabled(false);
|
||||||
return (0);
|
return (0);
|
||||||
}else{
|
}else{
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
zero_airspeed(false);
|
zero_airspeed(false);
|
||||||
cliSerial->printf("airspeed: ");
|
cliSerial->print("airspeed: ");
|
||||||
print_enabled(true);
|
print_enabled(true);
|
||||||
|
|
||||||
while(1) {
|
while(1) {
|
||||||
@ -492,7 +492,7 @@ int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
|
int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
cliSerial->printf("Uncalibrated relative airpressure\n");
|
cliSerial->println("Uncalibrated relative airpressure");
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
|
|
||||||
init_barometer(true);
|
init_barometer(true);
|
||||||
@ -519,11 +519,11 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
|
|||||||
void Plane::print_enabled(bool b)
|
void Plane::print_enabled(bool b)
|
||||||
{
|
{
|
||||||
if (b) {
|
if (b) {
|
||||||
cliSerial->printf("en");
|
cliSerial->print("en");
|
||||||
} else {
|
} else {
|
||||||
cliSerial->printf("dis");
|
cliSerial->print("dis");
|
||||||
}
|
}
|
||||||
cliSerial->printf("abled\n");
|
cliSerial->println("abled");
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CLI_ENABLED
|
#endif // CLI_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user