mirror of https://github.com/ArduPilot/ardupilot
Remove use of PSTR
The PSTR is already define as a NOP for all supported platforms. It's only needed for AVR so here we remove all the uses throughout the codebase. This was automated with a simple python script so it also converts places which spans to multiple lines, removing the matching parentheses. AVR-specific places were not changed.
This commit is contained in:
parent
bd0f0a7536
commit
2c38e31c93
|
@ -302,7 +302,7 @@ void Rover::one_second_loop(void)
|
|||
// write perf data every 20s
|
||||
if (counter % 10 == 0) {
|
||||
if (scheduler.debug() != 0) {
|
||||
hal.console->printf_P(PSTR("G_Dt_max=%lu\n"), (unsigned long)G_Dt_max);
|
||||
hal.console->printf_P("G_Dt_max=%lu\n", (unsigned long)G_Dt_max);
|
||||
}
|
||||
if (should_log(MASK_LOG_PM))
|
||||
Log_Write_Performance();
|
||||
|
|
|
@ -878,7 +878,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
||||
|
||||
// do command
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("command received: "));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"command received: ");
|
||||
|
||||
switch(packet.command) {
|
||||
|
||||
|
@ -1001,7 +1001,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
}
|
||||
else {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("Unsupported preflight calibration"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "Unsupported preflight calibration");
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -1137,10 +1137,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
// mark the firmware version in the tlog
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR(FIRMWARE_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, FIRMWARE_STRING);
|
||||
|
||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||
#endif
|
||||
handle_param_request_list(msg);
|
||||
break;
|
||||
|
@ -1366,7 +1366,7 @@ void Rover::mavlink_delay_cb()
|
|||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
last_5s = tnow;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Initialising APM..."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
|
||||
}
|
||||
check_usb_mux();
|
||||
|
||||
|
|
|
@ -24,16 +24,16 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&rover, &Rover::print_log
|
|||
|
||||
bool Rover::print_log_menu(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("logs enabled: "));
|
||||
cliSerial->printf_P("logs enabled: ");
|
||||
|
||||
if (0 == g.log_bitmask) {
|
||||
cliSerial->printf_P(PSTR("none"));
|
||||
cliSerial->printf_P("none");
|
||||
}else{
|
||||
// Macro to make the following code a bit easier on the eye.
|
||||
// Pass it the capitalised name of the log option, as defined
|
||||
// in defines.h but without the LOG_ prefix. It will check for
|
||||
// the bit being set and print the name of the log option to suit.
|
||||
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(PSTR(" %S"), PSTR(#_s))
|
||||
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(" %S", #_s)
|
||||
PLOG(ATTITUDE_FAST);
|
||||
PLOG(ATTITUDE_MED);
|
||||
PLOG(GPS);
|
||||
|
@ -70,11 +70,11 @@ int8_t Rover::dump_log(uint8_t argc, const Menu::arg *argv)
|
|||
DataFlash.DumpPageInfo(cliSerial);
|
||||
return(-1);
|
||||
} else if (dump_log_num <= 0) {
|
||||
cliSerial->printf_P(PSTR("dumping all\n"));
|
||||
cliSerial->printf_P("dumping all\n");
|
||||
Log_Read(0, 1, 0);
|
||||
return(-1);
|
||||
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
||||
cliSerial->printf_P(PSTR("bad log number\n"));
|
||||
cliSerial->printf_P("bad log number\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -97,7 +97,7 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
uint16_t bits;
|
||||
|
||||
if (argc != 2) {
|
||||
cliSerial->printf_P(PSTR("missing log type\n"));
|
||||
cliSerial->printf_P("missing log type\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -109,10 +109,10 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
// that name as the argument to the command, and set the bit in
|
||||
// bits accordingly.
|
||||
//
|
||||
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
||||
if (!strcasecmp_P(argv[1].str, "all")) {
|
||||
bits = ~0;
|
||||
} else {
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, #_s)) bits |= MASK_LOG_ ## _s
|
||||
TARG(ATTITUDE_FAST);
|
||||
TARG(ATTITUDE_MED);
|
||||
TARG(GPS);
|
||||
|
@ -130,7 +130,7 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
#undef TARG
|
||||
}
|
||||
|
||||
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
|
||||
if (!strcasecmp_P(argv[0].str, "enable")) {
|
||||
g.log_bitmask.set_and_save(g.log_bitmask | bits);
|
||||
}else{
|
||||
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
|
||||
|
@ -148,9 +148,9 @@ int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Rover::do_erase_logs(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\nErasing log...\n"));
|
||||
cliSerial->printf_P("\nErasing log...\n");
|
||||
DataFlash.EraseAll();
|
||||
cliSerial->printf_P(PSTR("\nLog erased.\n"));
|
||||
cliSerial->printf_P("\nLog erased.\n");
|
||||
}
|
||||
|
||||
|
||||
|
@ -391,12 +391,12 @@ void Rover::log_init(void)
|
|||
{
|
||||
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
if (!DataFlash.CardInserted()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("No dataflash card inserted"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "No dataflash card inserted");
|
||||
g.log_bitmask.set(0);
|
||||
} else if (DataFlash.NeedPrep()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Preparing log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Preparing log system");
|
||||
DataFlash.Prep();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Prepared log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Prepared log system");
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
gcs[i].reset_cli_timeout();
|
||||
}
|
||||
|
@ -411,11 +411,11 @@ void Rover::log_init(void)
|
|||
// Read the DataFlash log memory : Packet Parser
|
||||
void Rover::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
||||
"\nFree RAM: %u\n"),
|
||||
cliSerial->printf_P("\n" FIRMWARE_STRING
|
||||
"\nFree RAM: %u\n",
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
||||
cliSerial->println_P(HAL_BOARD_NAME);
|
||||
|
||||
DataFlash.LogReadProcess(list_entry, start_page, end_page,
|
||||
FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t),
|
||||
|
|
|
@ -566,26 +566,26 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
|
|||
void Rover::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
cliSerial->printf_P(PSTR("Bad var table\n"));
|
||||
hal.scheduler->panic(PSTR("Bad var table"));
|
||||
cliSerial->printf_P("Bad var table\n");
|
||||
hal.scheduler->panic("Bad var table");
|
||||
}
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||
cliSerial->printf_P("Firmware change: erasing EEPROM...\n");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println_P(PSTR("done."));
|
||||
cliSerial->println_P("done.");
|
||||
} else {
|
||||
unsigned long before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||
cliSerial->printf_P("load_all took %luus\n", micros() - before);
|
||||
}
|
||||
|
||||
// set a more reasonable default NAVL1_PERIOD for rovers
|
||||
|
|
|
@ -31,7 +31,7 @@ bool Rover::auto_check_trigger(void)
|
|||
|
||||
// check for user pressing the auto trigger to off
|
||||
if (auto_triggered && g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 1) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("AUTO triggered off"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "AUTO triggered off");
|
||||
auto_triggered = false;
|
||||
return false;
|
||||
}
|
||||
|
@ -49,7 +49,7 @@ bool Rover::auto_check_trigger(void)
|
|||
}
|
||||
|
||||
if (g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 0) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Triggered AUTO with pin"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");
|
||||
auto_triggered = true;
|
||||
return true;
|
||||
}
|
||||
|
@ -57,7 +57,7 @@ bool Rover::auto_check_trigger(void)
|
|||
if (!is_zero(g.auto_kickstart)) {
|
||||
float xaccel = ins.get_accel().x;
|
||||
if (xaccel >= g.auto_kickstart) {
|
||||
gcs_send_text_fmt(PSTR("Triggered AUTO xaccel=%.1f"), (double)xaccel);
|
||||
gcs_send_text_fmt("Triggered AUTO xaccel=%.1f", (double)xaccel);
|
||||
auto_triggered = true;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -30,7 +30,7 @@ void Rover::set_next_WP(const struct Location& loc)
|
|||
// location as the previous waypoint, to prevent immediately
|
||||
// considering the waypoint complete
|
||||
if (location_passed_point(current_loc, prev_WP, next_WP)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Resetting prev_WP"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Resetting prev_WP");
|
||||
prev_WP = current_loc;
|
||||
}
|
||||
|
||||
|
@ -63,7 +63,7 @@ void Rover::init_home()
|
|||
return;
|
||||
}
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("init home"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "init home");
|
||||
|
||||
ahrs.set_home(gps.location());
|
||||
home_is_set = true;
|
||||
|
|
|
@ -17,7 +17,7 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
return false;
|
||||
}
|
||||
|
||||
gcs_send_text_fmt(PSTR("Executing command ID #%i"),cmd.id);
|
||||
gcs_send_text_fmt("Executing command ID #%i",cmd.id);
|
||||
|
||||
// remember the course of our next navigation leg
|
||||
next_navigation_leg_cd = mission.get_next_ground_course_cd(0);
|
||||
|
@ -117,7 +117,7 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
void Rover::exit_mission()
|
||||
{
|
||||
if (control_mode == AUTO) {
|
||||
gcs_send_text_fmt(PSTR("No commands. Can't set AUTO - setting HOLD"));
|
||||
gcs_send_text_fmt("No commands. Can't set AUTO - setting HOLD");
|
||||
set_mode(HOLD);
|
||||
}
|
||||
}
|
||||
|
@ -164,7 +164,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
|||
// this is a command that doesn't require verify
|
||||
return true;
|
||||
}
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("verify_conditon: Unsupported command"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_conditon: Unsupported command");
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -203,7 +203,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
// Check if we need to loiter at this waypoint
|
||||
if (loiter_time_max > 0) {
|
||||
if (loiter_time == 0) { // check if we are just starting loiter
|
||||
gcs_send_text_fmt(PSTR("Reached Waypoint #%i - Loiter for %i seconds"),
|
||||
gcs_send_text_fmt("Reached Waypoint #%i - Loiter for %i seconds",
|
||||
(unsigned)cmd.index,
|
||||
(unsigned)loiter_time_max);
|
||||
// record the current time i.e. start timer
|
||||
|
@ -214,7 +214,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
return false;
|
||||
}
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
|
||||
gcs_send_text_fmt("Reached Waypoint #%i dist %um",
|
||||
(unsigned)cmd.index,
|
||||
(unsigned)get_distance(current_loc, next_WP));
|
||||
}
|
||||
|
@ -228,7 +228,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
// check if we have gone futher past the wp then last time and output new message if we have
|
||||
if ((uint32_t)distance_past_wp != (uint32_t)get_distance(current_loc, next_WP)) {
|
||||
distance_past_wp = get_distance(current_loc, next_WP);
|
||||
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
|
||||
gcs_send_text_fmt("Passed Waypoint #%i dist %um",
|
||||
(unsigned)cmd.index,
|
||||
(unsigned)distance_past_wp);
|
||||
}
|
||||
|
@ -248,14 +248,14 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
bool Rover::verify_RTL()
|
||||
{
|
||||
if (wp_distance <= g.waypoint_radius) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Reached Destination"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached Destination");
|
||||
rtl_complete = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// have we gone past the waypoint?
|
||||
if (location_passed_point(current_loc, prev_WP, next_WP)) {
|
||||
gcs_send_text_fmt(PSTR("Reached Destination: Distance away %um"),
|
||||
gcs_send_text_fmt("Reached Destination: Distance away %um",
|
||||
(unsigned)get_distance(current_loc, next_WP));
|
||||
rtl_complete = true;
|
||||
return true;
|
||||
|
@ -309,12 +309,12 @@ void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
|||
{
|
||||
if (cmd.content.speed.target_ms > 0) {
|
||||
g.speed_cruise.set(cmd.content.speed.target_ms);
|
||||
gcs_send_text_fmt(PSTR("Cruise speed: %.1f m/s"), (double)g.speed_cruise.get());
|
||||
gcs_send_text_fmt("Cruise speed: %.1f m/s", (double)g.speed_cruise.get());
|
||||
}
|
||||
|
||||
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
|
||||
g.throttle_cruise.set(cmd.content.speed.throttle_pct);
|
||||
gcs_send_text_fmt(PSTR("Cruise throttle: %.1f"), g.throttle_cruise.get());
|
||||
gcs_send_text_fmt("Cruise throttle: %.1f", g.throttle_cruise.get());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -83,7 +83,7 @@ void Rover::read_trim_switch()
|
|||
ch7_flag = false;
|
||||
|
||||
if (control_mode == MANUAL) {
|
||||
hal.console->println_P(PSTR("Erasing waypoints"));
|
||||
hal.console->println_P("Erasing waypoints");
|
||||
// if SW7 is ON in MANUAL = Erase the Flight Plan
|
||||
mission.clear();
|
||||
if (channel_steer->control_in > 3000) {
|
||||
|
@ -105,7 +105,7 @@ void Rover::read_trim_switch()
|
|||
|
||||
// save command
|
||||
if(mission.add_cmd(cmd)) {
|
||||
hal.console->printf_P(PSTR("Learning waypoint %u"), (unsigned)mission.num_commands());
|
||||
hal.console->printf_P("Learning waypoint %u", (unsigned)mission.num_commands());
|
||||
}
|
||||
} else if (control_mode == AUTO) {
|
||||
// if SW7 is ON in AUTO = set to RTL
|
||||
|
|
|
@ -22,7 +22,7 @@ void Rover::navigate()
|
|||
wp_distance = get_distance(current_loc, next_WP);
|
||||
|
||||
if (wp_distance < 0){
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("<navigate> WP error - distance < 0"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"<navigate> WP error - distance < 0");
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -4,9 +4,9 @@
|
|||
|
||||
void Rover::init_barometer(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Calibrating barometer"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
|
||||
barometer.calibrate();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("barometer calibration complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
|
||||
}
|
||||
|
||||
void Rover::init_sonar(void)
|
||||
|
@ -56,7 +56,7 @@ void Rover::read_sonars(void)
|
|||
obstacle.detected_count++;
|
||||
}
|
||||
if (obstacle.detected_count == g.sonar_debounce) {
|
||||
gcs_send_text_fmt(PSTR("Sonar1 obstacle %u cm"),
|
||||
gcs_send_text_fmt("Sonar1 obstacle %u cm",
|
||||
(unsigned)obstacle.sonar1_distance_cm);
|
||||
}
|
||||
obstacle.detected_time_ms = hal.scheduler->millis();
|
||||
|
@ -67,7 +67,7 @@ void Rover::read_sonars(void)
|
|||
obstacle.detected_count++;
|
||||
}
|
||||
if (obstacle.detected_count == g.sonar_debounce) {
|
||||
gcs_send_text_fmt(PSTR("Sonar2 obstacle %u cm"),
|
||||
gcs_send_text_fmt("Sonar2 obstacle %u cm",
|
||||
(unsigned)obstacle.sonar2_distance_cm);
|
||||
}
|
||||
obstacle.detected_time_ms = hal.scheduler->millis();
|
||||
|
@ -83,7 +83,7 @@ void Rover::read_sonars(void)
|
|||
obstacle.detected_count++;
|
||||
}
|
||||
if (obstacle.detected_count == g.sonar_debounce) {
|
||||
gcs_send_text_fmt(PSTR("Sonar obstacle %u cm"),
|
||||
gcs_send_text_fmt("Sonar obstacle %u cm",
|
||||
(unsigned)obstacle.sonar1_distance_cm);
|
||||
}
|
||||
obstacle.detected_time_ms = hal.scheduler->millis();
|
||||
|
@ -96,7 +96,7 @@ void Rover::read_sonars(void)
|
|||
// no object detected - reset after the turn time
|
||||
if (obstacle.detected_count >= g.sonar_debounce &&
|
||||
hal.scheduler->millis() > obstacle.detected_time_ms + g.sonar_turn_time*1000) {
|
||||
gcs_send_text_fmt(PSTR("Obstacle passed"));
|
||||
gcs_send_text_fmt("Obstacle passed");
|
||||
obstacle.detected_count = 0;
|
||||
obstacle.turn_angle = 0;
|
||||
}
|
||||
|
|
|
@ -18,12 +18,12 @@ MENU(setup_menu, "setup", setup_menu_commands);
|
|||
int8_t Rover::setup_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
// Give the user some guidance
|
||||
cliSerial->printf_P(PSTR("Setup Mode\n"
|
||||
cliSerial->printf_P("Setup Mode\n"
|
||||
"\n"
|
||||
"IMPORTANT: if you have not previously set this system up, use the\n"
|
||||
"'reset' command to initialize the EEPROM to sensible default values\n"
|
||||
"and then the 'radio' command to configure for your radio.\n"
|
||||
"\n"));
|
||||
"\n");
|
||||
|
||||
// Run the setup menu. When the menu exits, we will return to the main menu.
|
||||
setup_menu.run();
|
||||
|
@ -34,7 +34,7 @@ int8_t Rover::setup_erase(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
int c;
|
||||
|
||||
cliSerial->printf_P(PSTR("\nType 'Y' and hit Enter to erase all waypoint and parameter data, any other key to abort: "));
|
||||
cliSerial->printf_P("\nType 'Y' and hit Enter to erase all waypoint and parameter data, any other key to abort: ");
|
||||
|
||||
do {
|
||||
c = cliSerial->read();
|
||||
|
@ -48,9 +48,9 @@ int8_t Rover::setup_erase(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Rover::zero_eeprom(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
|
||||
cliSerial->printf_P("\nErasing EEPROM\n");
|
||||
StorageManager::erase();
|
||||
cliSerial->printf_P(PSTR("done\n"));
|
||||
cliSerial->printf_P("done\n");
|
||||
}
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
|
|
@ -11,17 +11,15 @@ The init_ardupilot function processes everything we need for an in - air restart
|
|||
#if CLI_ENABLED == ENABLED
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of print_f that reads from flash memory
|
||||
int8_t Rover::main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Commands:\n"
|
||||
cliSerial->printf_P("Commands:\n"
|
||||
" logs log readback/setup mode\n"
|
||||
" setup setup mode\n"
|
||||
" test test mode\n"
|
||||
"\n"
|
||||
"Move the slide switch and reset to FLY.\n"
|
||||
"\n"));
|
||||
"\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -85,8 +83,8 @@ void Rover::init_ardupilot()
|
|||
// initialise console serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n"),
|
||||
cliSerial->printf_P("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n",
|
||||
hal.util->available_memory());
|
||||
|
||||
//
|
||||
|
@ -155,7 +153,7 @@ void Rover::init_ardupilot()
|
|||
|
||||
if (g.compass_enabled==true) {
|
||||
if (!compass.init()|| !compass.read()) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
cliSerial->println_P("Compass initialisation failed!");
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
|
@ -199,7 +197,7 @@ void Rover::init_ardupilot()
|
|||
// menu; they must reset in order to fly.
|
||||
//
|
||||
if (g.cli_enabled == 1) {
|
||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||
cliSerial->println_P(msg);
|
||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||
gcs[1].get_uart()->println_P(msg);
|
||||
|
@ -228,10 +226,10 @@ void Rover::startup_ground(void)
|
|||
{
|
||||
set_mode(INITIALISING);
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("<startup_ground> GROUND START"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
|
||||
|
||||
#if(GROUND_START_DELAY > 0)
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("<startup_ground> With Delay"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
|
||||
delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
|
@ -255,7 +253,7 @@ void Rover::startup_ground(void)
|
|||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
ins.set_dataflash(&DataFlash);
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("\n\n Ready to drive."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"\n\n Ready to drive.");
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -366,7 +364,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||
}
|
||||
if (failsafe.triggered != 0 && failsafe.bits == 0) {
|
||||
// a failsafe event has ended
|
||||
gcs_send_text_fmt(PSTR("Failsafe ended"));
|
||||
gcs_send_text_fmt("Failsafe ended");
|
||||
}
|
||||
|
||||
failsafe.triggered &= failsafe.bits;
|
||||
|
@ -377,7 +375,7 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||
control_mode != RTL &&
|
||||
control_mode != HOLD) {
|
||||
failsafe.triggered = failsafe.bits;
|
||||
gcs_send_text_fmt(PSTR("Failsafe trigger 0x%x"), (unsigned)failsafe.triggered);
|
||||
gcs_send_text_fmt("Failsafe trigger 0x%x", (unsigned)failsafe.triggered);
|
||||
switch (g.fs_action) {
|
||||
case 0:
|
||||
break;
|
||||
|
@ -393,12 +391,12 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
|
|||
|
||||
void Rover::startup_INS_ground(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, PSTR("Warming up ADC..."));
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, "Warming up ADC...");
|
||||
mavlink_delay(500);
|
||||
|
||||
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
|
||||
// -----------------------
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, PSTR("Beginning INS calibration; do not move vehicle"));
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move vehicle");
|
||||
mavlink_delay(1000);
|
||||
|
||||
ahrs.init();
|
||||
|
@ -452,25 +450,25 @@ void Rover::print_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
{
|
||||
switch (mode) {
|
||||
case MANUAL:
|
||||
port->print_P(PSTR("Manual"));
|
||||
port->print_P("Manual");
|
||||
break;
|
||||
case HOLD:
|
||||
port->print_P(PSTR("HOLD"));
|
||||
port->print_P("HOLD");
|
||||
break;
|
||||
case LEARNING:
|
||||
port->print_P(PSTR("Learning"));
|
||||
port->print_P("Learning");
|
||||
break;
|
||||
case STEERING:
|
||||
port->print_P(PSTR("Steering"));
|
||||
port->print_P("Steering");
|
||||
break;
|
||||
case AUTO:
|
||||
port->print_P(PSTR("AUTO"));
|
||||
port->print_P("AUTO");
|
||||
break;
|
||||
case RTL:
|
||||
port->print_P(PSTR("RTL"));
|
||||
port->print_P("RTL");
|
||||
break;
|
||||
default:
|
||||
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
||||
port->printf_P("Mode(%u)", (unsigned)mode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -34,14 +34,14 @@ MENU(test_menu, "test", test_menu_commands);
|
|||
|
||||
int8_t Rover::test_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Test Mode\n\n"));
|
||||
cliSerial->printf_P("Test Mode\n\n");
|
||||
test_menu.run();
|
||||
return 0;
|
||||
}
|
||||
|
||||
void Rover::print_hit_enter()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
cliSerial->printf_P("Hit Enter to exit.\n\n");
|
||||
}
|
||||
|
||||
int8_t Rover::test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
||||
|
@ -56,7 +56,7 @@ int8_t Rover::test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
|||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
|
||||
cliSerial->printf_P(PSTR("IN:\t1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
cliSerial->printf_P("IN:\t1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n",
|
||||
channel_steer->radio_in,
|
||||
g.rc_2.radio_in,
|
||||
channel_throttle->radio_in,
|
||||
|
@ -118,7 +118,7 @@ int8_t Rover::test_radio(uint8_t argc, const Menu::arg *argv)
|
|||
// ------------------------------
|
||||
set_servos();
|
||||
|
||||
cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
cliSerial->printf_P("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n",
|
||||
channel_steer->control_in,
|
||||
g.rc_2.control_in,
|
||||
channel_throttle->control_in,
|
||||
|
@ -149,7 +149,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
oldSwitchPosition = readSwitch();
|
||||
|
||||
cliSerial->printf_P(PSTR("Unplug battery, throttle in neutral, turn off radio.\n"));
|
||||
cliSerial->printf_P("Unplug battery, throttle in neutral, turn off radio.\n");
|
||||
while(channel_throttle->control_in > 0){
|
||||
delay(20);
|
||||
read_radio();
|
||||
|
@ -160,19 +160,19 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
read_radio();
|
||||
|
||||
if(channel_throttle->control_in > 0){
|
||||
cliSerial->printf_P(PSTR("THROTTLE CHANGED %d \n"), channel_throttle->control_in);
|
||||
cliSerial->printf_P("THROTTLE CHANGED %d \n", channel_throttle->control_in);
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if (oldSwitchPosition != readSwitch()){
|
||||
cliSerial->printf_P(PSTR("CONTROL MODE CHANGED: "));
|
||||
cliSerial->printf_P("CONTROL MODE CHANGED: ");
|
||||
print_mode(cliSerial, readSwitch());
|
||||
cliSerial->println();
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if(throttle_failsafe_active()) {
|
||||
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), channel_throttle->radio_in);
|
||||
cliSerial->printf_P("THROTTLE FAILSAFE ACTIVATED: %d, ", channel_throttle->radio_in);
|
||||
print_mode(cliSerial, readSwitch());
|
||||
cliSerial->println();
|
||||
fail_test++;
|
||||
|
@ -182,7 +182,7 @@ int8_t Rover::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
return (0);
|
||||
}
|
||||
if(cliSerial->available() > 0){
|
||||
cliSerial->printf_P(PSTR("LOS caused no change in APM.\n"));
|
||||
cliSerial->printf_P("LOS caused no change in APM.\n");
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
@ -194,14 +194,14 @@ int8_t Rover::test_relay(uint8_t argc, const Menu::arg *argv)
|
|||
delay(1000);
|
||||
|
||||
while(1){
|
||||
cliSerial->printf_P(PSTR("Relay on\n"));
|
||||
cliSerial->printf_P("Relay on\n");
|
||||
relay.on(0);
|
||||
delay(3000);
|
||||
if(cliSerial->available() > 0){
|
||||
return (0);
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("Relay off\n"));
|
||||
cliSerial->printf_P("Relay off\n");
|
||||
relay.off(0);
|
||||
delay(3000);
|
||||
if(cliSerial->available() > 0){
|
||||
|
@ -214,8 +214,8 @@ int8_t Rover::test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
delay(1000);
|
||||
|
||||
cliSerial->printf_P(PSTR("%u waypoints\n"), (unsigned)mission.num_commands());
|
||||
cliSerial->printf_P(PSTR("Hit radius: %f\n"), g.waypoint_radius);
|
||||
cliSerial->printf_P("%u waypoints\n", (unsigned)mission.num_commands());
|
||||
cliSerial->printf_P("Hit radius: %f\n", g.waypoint_radius);
|
||||
|
||||
for(uint8_t i = 0; i < mission.num_commands(); i++){
|
||||
AP_Mission::Mission_Command temp_cmd;
|
||||
|
@ -229,7 +229,7 @@ int8_t Rover::test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Rover::test_wp_print(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
|
||||
cliSerial->printf_P("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n",
|
||||
(int)cmd.index,
|
||||
(int)cmd.id,
|
||||
(int)cmd.content.location.options,
|
||||
|
@ -244,7 +244,7 @@ int8_t Rover::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
cliSerial->printf_P(PSTR("Control CH "));
|
||||
cliSerial->printf_P("Control CH ");
|
||||
|
||||
cliSerial->println(MODE_CHANNEL, BASE_DEC);
|
||||
|
||||
|
@ -252,7 +252,7 @@ int8_t Rover::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||
delay(20);
|
||||
uint8_t switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition){
|
||||
cliSerial->printf_P(PSTR("Position %d\n"), switchPosition);
|
||||
cliSerial->printf_P("Position %d\n", switchPosition);
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
if(cliSerial->available() > 0){
|
||||
|
@ -266,7 +266,7 @@ int8_t Rover::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||
*/
|
||||
int8_t Rover::test_logging(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->println_P(PSTR("Testing dataflash logging"));
|
||||
cliSerial->println_P("Testing dataflash logging");
|
||||
DataFlash.ShowDeviceInfo(cliSerial);
|
||||
return 0;
|
||||
}
|
||||
|
@ -289,13 +289,13 @@ int8_t Rover::test_gps(uint8_t argc, const Menu::arg *argv)
|
|||
if (gps.last_message_time_ms() != last_message_time_ms) {
|
||||
last_message_time_ms = gps.last_message_time_ms();
|
||||
const Location &loc = gps.location();
|
||||
cliSerial->printf_P(PSTR("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n"),
|
||||
cliSerial->printf_P("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n",
|
||||
(long)loc.lat,
|
||||
(long)loc.lng,
|
||||
(long)loc.alt/100,
|
||||
(int)gps.num_sats());
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("."));
|
||||
cliSerial->printf_P(".");
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
|
@ -305,7 +305,7 @@ int8_t Rover::test_gps(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
int8_t Rover::test_ins(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
//cliSerial->printf_P(PSTR("Calibrating."));
|
||||
//cliSerial->printf_P("Calibrating.");
|
||||
ahrs.init();
|
||||
ahrs.set_fly_forward(true);
|
||||
ins.init(ins_sample_rate);
|
||||
|
@ -333,7 +333,7 @@ int8_t Rover::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
// ---------------------
|
||||
Vector3f gyros = ins.get_gyro();
|
||||
Vector3f accels = ins.get_accel();
|
||||
cliSerial->printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
|
||||
cliSerial->printf_P("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n",
|
||||
(int)ahrs.roll_sensor / 100,
|
||||
(int)ahrs.pitch_sensor / 100,
|
||||
(uint16_t)ahrs.yaw_sensor / 100,
|
||||
|
@ -348,22 +348,22 @@ int8_t Rover::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
void Rover::print_enabled(bool b)
|
||||
{
|
||||
if(b)
|
||||
cliSerial->printf_P(PSTR("en"));
|
||||
cliSerial->printf_P("en");
|
||||
else
|
||||
cliSerial->printf_P(PSTR("dis"));
|
||||
cliSerial->printf_P(PSTR("abled\n"));
|
||||
cliSerial->printf_P("dis");
|
||||
cliSerial->printf_P("abled\n");
|
||||
}
|
||||
|
||||
int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
if (!g.compass_enabled) {
|
||||
cliSerial->printf_P(PSTR("Compass: "));
|
||||
cliSerial->printf_P("Compass: ");
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}
|
||||
|
||||
if (!compass.init()) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
cliSerial->println_P("Compass initialisation failed!");
|
||||
return 0;
|
||||
}
|
||||
ahrs.init();
|
||||
|
@ -401,12 +401,12 @@ int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
if (compass.healthy()) {
|
||||
const Vector3f mag_ofs = compass.get_offsets();
|
||||
const Vector3f mag = compass.get_field();
|
||||
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||
cliSerial->printf_P("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n",
|
||||
(wrap_360_cd(ToDeg(heading) * 100)) /100,
|
||||
(double)mag.x, (double)mag.y, (double)mag.z,
|
||||
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
|
||||
} else {
|
||||
cliSerial->println_P(PSTR("compass not healthy"));
|
||||
cliSerial->println_P("compass not healthy");
|
||||
}
|
||||
counter=0;
|
||||
}
|
||||
|
@ -417,7 +417,7 @@ int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
// save offsets. This allows you to get sane offset values using
|
||||
// the CLI before you go flying.
|
||||
cliSerial->println_P(PSTR("saving offsets"));
|
||||
cliSerial->println_P("saving offsets");
|
||||
compass.save_offsets();
|
||||
return (0);
|
||||
}
|
||||
|
@ -432,7 +432,7 @@ int8_t Rover::test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
sonar.update();
|
||||
|
||||
if (sonar.status() == RangeFinder::RangeFinder_NotConnected) {
|
||||
cliSerial->println_P(PSTR("WARNING: Sonar is not enabled"));
|
||||
cliSerial->println_P("WARNING: Sonar is not enabled");
|
||||
}
|
||||
|
||||
print_hit_enter();
|
||||
|
@ -473,7 +473,7 @@ int8_t Rover::test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
voltage2_max = max(voltage2_max, voltage);
|
||||
|
||||
if (now - last_print >= 200) {
|
||||
cliSerial->printf_P(PSTR("sonar1 dist=%.1f:%.1fcm volt1=%.2f:%.2f sonar2 dist=%.1f:%.1fcm volt2=%.2f:%.2f\n"),
|
||||
cliSerial->printf_P("sonar1 dist=%.1f:%.1fcm volt1=%.2f:%.2f sonar2 dist=%.1f:%.1fcm volt2=%.2f:%.2f\n",
|
||||
(double)sonar_dist_cm_min,
|
||||
(double)sonar_dist_cm_max,
|
||||
(double)voltage_min,
|
||||
|
|
|
@ -599,7 +599,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
||||
|
||||
// do command
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("command received: "));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"command received: ");
|
||||
|
||||
switch(packet.command) {
|
||||
|
||||
|
@ -827,7 +827,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
// check if this is the HOME wp
|
||||
if (packet.seq == 0) {
|
||||
tracker.set_home(tell_command); // New home in EEPROM
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("new HOME received"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"new HOME received");
|
||||
waypoint_receiving = false;
|
||||
}
|
||||
|
||||
|
@ -919,7 +919,7 @@ void Tracker::mavlink_delay_cb()
|
|||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
last_5s = tnow;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Initialising APM..."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
|
||||
}
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
|
|
@ -288,16 +288,16 @@ void Tracker::load_parameters(void)
|
|||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
hal.console->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||
hal.console->printf_P("Firmware change: erasing EEPROM...\n");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
hal.console->println_P(PSTR("done."));
|
||||
hal.console->println_P("done.");
|
||||
} else {
|
||||
uint32_t before = hal.scheduler->micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
hal.console->printf_P(PSTR("load_all took %luus\n"), (unsigned long)(hal.scheduler->micros() - before));
|
||||
hal.console->printf_P("load_all took %luus\n", (unsigned long)(hal.scheduler->micros() - before));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -4,9 +4,9 @@
|
|||
|
||||
void Tracker::init_barometer(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Calibrating barometer"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
|
||||
barometer.calibrate();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("barometer calibration complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
|
||||
}
|
||||
|
||||
// read the barometer and return the updated altitude in meters
|
||||
|
|
|
@ -248,7 +248,7 @@ void Tracker::update_yaw_position_servo(float yaw)
|
|||
}
|
||||
|
||||
if (new_slew_dir != slew_dir) {
|
||||
tracker.gcs_send_text_fmt(PSTR("SLEW: %d/%d err=%ld servo=%ld ez=%.3f"),
|
||||
tracker.gcs_send_text_fmt("SLEW: %d/%d err=%ld servo=%ld ez=%.3f",
|
||||
(int)slew_dir, (int)new_slew_dir,
|
||||
(long)angle_err,
|
||||
(long)channel_yaw.servo_out,
|
||||
|
|
|
@ -20,8 +20,8 @@ void Tracker::init_tracker()
|
|||
// initialise console serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
hal.console->printf_P(PSTR("\n\nInit " THISFIRMWARE
|
||||
"\n\nFree RAM: %u\n"),
|
||||
hal.console->printf_P("\n\nInit " THISFIRMWARE
|
||||
"\n\nFree RAM: %u\n",
|
||||
hal.util->available_memory());
|
||||
|
||||
// Check the EEPROM format version before loading any parameters from EEPROM
|
||||
|
@ -68,7 +68,7 @@ void Tracker::init_tracker()
|
|||
|
||||
if (g.compass_enabled==true) {
|
||||
if (!compass.init() || !compass.read()) {
|
||||
hal.console->println_P(PSTR("Compass initialisation failed!"));
|
||||
hal.console->println_P("Compass initialisation failed!");
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
|
@ -98,7 +98,7 @@ void Tracker::init_tracker()
|
|||
if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) {
|
||||
current_loc.lat = g.start_latitude * 1.0e7f;
|
||||
current_loc.lng = g.start_longitude * 1.0e7f;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("ignoring invalid START_LATITUDE or START_LONGITUDE parameter"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
|
||||
}
|
||||
|
||||
// see if EEPROM has a default location as well
|
||||
|
@ -108,7 +108,7 @@ void Tracker::init_tracker()
|
|||
|
||||
init_capabilities();
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("\nReady to track."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"\nReady to track.");
|
||||
hal.scheduler->delay(1000); // Why????
|
||||
|
||||
set_mode(AUTO); // tracking
|
||||
|
|
|
@ -43,15 +43,15 @@ void Copter::set_simple_mode(uint8_t b)
|
|||
if(ap.simple_mode != b){
|
||||
if(b == 0){
|
||||
Log_Write_Event(DATA_SET_SIMPLE_OFF);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, PSTR("Simple:OFF"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Simple:OFF");
|
||||
}else if(b == 1){
|
||||
Log_Write_Event(DATA_SET_SIMPLE_ON);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, PSTR("Simple:ON"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Simple:ON");
|
||||
}else{
|
||||
// initialise super simple heading
|
||||
update_super_simple_bearing(true);
|
||||
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, PSTR("SuperSimple:ON"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SuperSimple:ON");
|
||||
}
|
||||
ap.simple_mode = b;
|
||||
}
|
||||
|
|
|
@ -206,7 +206,7 @@ void Copter::perf_update(void)
|
|||
if (should_log(MASK_LOG_PM))
|
||||
Log_Write_Performance();
|
||||
if (scheduler.debug()) {
|
||||
gcs_send_text_fmt(PSTR("PERF: %u/%u %lu %lu\n"),
|
||||
gcs_send_text_fmt("PERF: %u/%u %lu %lu\n",
|
||||
(unsigned)perf_info_get_num_long_running(),
|
||||
(unsigned)perf_info_get_num_loops(),
|
||||
(unsigned long)perf_info_get_max_time(),
|
||||
|
|
|
@ -1022,12 +1022,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: // MAV ID: 21
|
||||
{
|
||||
// mark the firmware version in the tlog
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR(FIRMWARE_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, FIRMWARE_STRING);
|
||||
|
||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||
#endif
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "Frame: " FRAME_CONFIG_STRING);
|
||||
handle_param_request_list(msg);
|
||||
break;
|
||||
}
|
||||
|
@ -1518,13 +1518,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
case MAV_CMD_DO_SEND_BANNER: {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR(FIRMWARE_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, FIRMWARE_STRING);
|
||||
|
||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||
#endif
|
||||
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "Frame: " FRAME_CONFIG_STRING);
|
||||
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_APM1 && CONFIG_HAL_BOARD != HAL_BOARD_APM2
|
||||
// send system ID if we can
|
||||
|
@ -1846,12 +1846,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
if (packet.idx >= copter.rally.get_rally_total() ||
|
||||
packet.idx >= copter.rally.get_rally_max()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad rally point message ID"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad rally point message ID");
|
||||
break;
|
||||
}
|
||||
|
||||
if (packet.count != copter.rally.get_rally_total()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad rally point message count"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad rally point message count");
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1864,7 +1864,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
rally_point.flags = packet.flags;
|
||||
|
||||
if (!copter.rally.set_rally_point_with_index(packet.idx, rally_point)) {
|
||||
send_text_P(MAV_SEVERITY_CRITICAL, PSTR("error setting rally point"));
|
||||
send_text_P(MAV_SEVERITY_CRITICAL, "error setting rally point");
|
||||
}
|
||||
|
||||
break;
|
||||
|
@ -1872,27 +1872,27 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
//send a rally point to the GCS
|
||||
case MAVLINK_MSG_ID_RALLY_FETCH_POINT: {
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, PSTR("## getting rally point in GCS_Mavlink.cpp 1")); // #### TEMP
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, "## getting rally point in GCS_Mavlink.cpp 1"); // #### TEMP
|
||||
|
||||
mavlink_rally_fetch_point_t packet;
|
||||
mavlink_msg_rally_fetch_point_decode(msg, &packet);
|
||||
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, PSTR("## getting rally point in GCS_Mavlink.cpp 2")); // #### TEMP
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, "## getting rally point in GCS_Mavlink.cpp 2"); // #### TEMP
|
||||
|
||||
if (packet.idx > copter.rally.get_rally_total()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("bad rally point index"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "bad rally point index");
|
||||
break;
|
||||
}
|
||||
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, PSTR("## getting rally point in GCS_Mavlink.cpp 3")); // #### TEMP
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, "## getting rally point in GCS_Mavlink.cpp 3"); // #### TEMP
|
||||
|
||||
RallyLocation rally_point;
|
||||
if (!copter.rally.get_rally_point_with_index(packet.idx, rally_point)) {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("failed to set rally point"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "failed to set rally point");
|
||||
break;
|
||||
}
|
||||
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, PSTR("## getting rally point in GCS_Mavlink.cpp 4")); // #### TEMP
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, "## getting rally point in GCS_Mavlink.cpp 4"); // #### TEMP
|
||||
|
||||
mavlink_msg_rally_point_send_buf(msg,
|
||||
chan, msg->sysid, msg->compid, packet.idx,
|
||||
|
@ -1900,7 +1900,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
rally_point.alt, rally_point.break_alt, rally_point.land_dir,
|
||||
rally_point.flags);
|
||||
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, PSTR("## getting rally point in GCS_Mavlink.cpp 5")); // #### TEMP
|
||||
//send_text_P(MAV_SEVERITY_CRITICAL, "## getting rally point in GCS_Mavlink.cpp 5"); // #### TEMP
|
||||
|
||||
break;
|
||||
}
|
||||
|
@ -1970,7 +1970,7 @@ void Copter::mavlink_delay_cb()
|
|||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
last_5s = tnow;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Initialising APM..."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
|
||||
}
|
||||
check_usb_mux();
|
||||
|
||||
|
|
|
@ -25,26 +25,26 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&copter, &Copter::print_l
|
|||
|
||||
bool Copter::print_log_menu(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("logs enabled: "));
|
||||
cliSerial->printf_P("logs enabled: ");
|
||||
|
||||
if (0 == g.log_bitmask) {
|
||||
cliSerial->printf_P(PSTR("none"));
|
||||
cliSerial->printf_P("none");
|
||||
}else{
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) cliSerial->printf_P(PSTR(" ATTITUDE_FAST"));
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) cliSerial->printf_P(PSTR(" ATTITUDE_MED"));
|
||||
if (g.log_bitmask & MASK_LOG_GPS) cliSerial->printf_P(PSTR(" GPS"));
|
||||
if (g.log_bitmask & MASK_LOG_PM) cliSerial->printf_P(PSTR(" PM"));
|
||||
if (g.log_bitmask & MASK_LOG_CTUN) cliSerial->printf_P(PSTR(" CTUN"));
|
||||
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf_P(PSTR(" NTUN"));
|
||||
if (g.log_bitmask & MASK_LOG_RCIN) cliSerial->printf_P(PSTR(" RCIN"));
|
||||
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
|
||||
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(PSTR(" CMD"));
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(PSTR(" CURRENT"));
|
||||
if (g.log_bitmask & MASK_LOG_RCOUT) cliSerial->printf_P(PSTR(" RCOUT"));
|
||||
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(PSTR(" OPTFLOW"));
|
||||
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(PSTR(" COMPASS"));
|
||||
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf_P(PSTR(" CAMERA"));
|
||||
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(PSTR(" PID"));
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST) cliSerial->printf_P(" ATTITUDE_FAST");
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) cliSerial->printf_P(" ATTITUDE_MED");
|
||||
if (g.log_bitmask & MASK_LOG_GPS) cliSerial->printf_P(" GPS");
|
||||
if (g.log_bitmask & MASK_LOG_PM) cliSerial->printf_P(" PM");
|
||||
if (g.log_bitmask & MASK_LOG_CTUN) cliSerial->printf_P(" CTUN");
|
||||
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf_P(" NTUN");
|
||||
if (g.log_bitmask & MASK_LOG_RCIN) cliSerial->printf_P(" RCIN");
|
||||
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(" IMU");
|
||||
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(" CMD");
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(" CURRENT");
|
||||
if (g.log_bitmask & MASK_LOG_RCOUT) cliSerial->printf_P(" RCOUT");
|
||||
if (g.log_bitmask & MASK_LOG_OPTFLOW) cliSerial->printf_P(" OPTFLOW");
|
||||
if (g.log_bitmask & MASK_LOG_COMPASS) cliSerial->printf_P(" COMPASS");
|
||||
if (g.log_bitmask & MASK_LOG_CAMERA) cliSerial->printf_P(" CAMERA");
|
||||
if (g.log_bitmask & MASK_LOG_PID) cliSerial->printf_P(" PID");
|
||||
}
|
||||
|
||||
cliSerial->println();
|
||||
|
@ -68,11 +68,11 @@ int8_t Copter::dump_log(uint8_t argc, const Menu::arg *argv)
|
|||
DataFlash.DumpPageInfo(cliSerial);
|
||||
return(-1);
|
||||
} else if (dump_log_num <= 0) {
|
||||
cliSerial->printf_P(PSTR("dumping all\n"));
|
||||
cliSerial->printf_P("dumping all\n");
|
||||
Log_Read(0, 1, 0);
|
||||
return(-1);
|
||||
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
||||
cliSerial->printf_P(PSTR("bad log number\n"));
|
||||
cliSerial->printf_P("bad log number\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -95,7 +95,7 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
uint16_t bits;
|
||||
|
||||
if (argc != 2) {
|
||||
cliSerial->printf_P(PSTR("missing log type\n"));
|
||||
cliSerial->printf_P("missing log type\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -107,10 +107,10 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
// that name as the argument to the command, and set the bit in
|
||||
// bits accordingly.
|
||||
//
|
||||
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
||||
if (!strcasecmp_P(argv[1].str, "all")) {
|
||||
bits = ~0;
|
||||
} else {
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(# _s))) bits |= MASK_LOG_ ## _s
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
|
||||
TARG(ATTITUDE_FAST);
|
||||
TARG(ATTITUDE_MED);
|
||||
TARG(GPS);
|
||||
|
@ -129,7 +129,7 @@ int8_t Copter::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
#undef TARG
|
||||
}
|
||||
|
||||
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
|
||||
if (!strcasecmp_P(argv[0].str, "enable")) {
|
||||
g.log_bitmask.set_and_save(g.log_bitmask | bits);
|
||||
}else{
|
||||
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
|
||||
|
@ -147,9 +147,9 @@ int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Copter::do_erase_logs(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Erasing logs\n"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Erasing logs\n");
|
||||
DataFlash.EraseAll();
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Log erase complete\n"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Log erase complete\n");
|
||||
}
|
||||
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
|
@ -767,12 +767,12 @@ const struct LogStructure Copter::log_structure[] PROGMEM = {
|
|||
// Read the DataFlash log memory
|
||||
void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
||||
cliSerial->printf_P("\n" FIRMWARE_STRING
|
||||
"\nFree RAM: %u\n"
|
||||
"\nFrame: " FRAME_CONFIG_STRING "\n"),
|
||||
"\nFrame: " FRAME_CONFIG_STRING "\n",
|
||||
(unsigned) hal.util->available_memory());
|
||||
|
||||
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
||||
cliSerial->println_P(HAL_BOARD_NAME);
|
||||
|
||||
DataFlash.LogReadProcess(list_entry, start_page, end_page,
|
||||
FUNCTOR_BIND_MEMBER(&Copter::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),
|
||||
|
@ -783,7 +783,7 @@ void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_pag
|
|||
void Copter::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by DataFlash
|
||||
DataFlash.Log_Write_Message_P(PSTR("Frame: " FRAME_CONFIG_STRING));
|
||||
DataFlash.Log_Write_Message_P("Frame: " FRAME_CONFIG_STRING);
|
||||
DataFlash.Log_Write_Mode(control_mode);
|
||||
}
|
||||
|
||||
|
@ -807,12 +807,12 @@ void Copter::log_init(void)
|
|||
{
|
||||
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
if (!DataFlash.CardInserted()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("No dataflash inserted"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "No dataflash inserted");
|
||||
g.log_bitmask.set(0);
|
||||
} else if (DataFlash.NeedPrep()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Preparing log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Preparing log system");
|
||||
DataFlash.Prep();
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Prepared log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Prepared log system");
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
gcs[i].reset_cli_timeout();
|
||||
}
|
||||
|
|
|
@ -1148,8 +1148,8 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
|
|||
void Copter::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
cliSerial->printf_P(PSTR("Bad var table\n"));
|
||||
hal.scheduler->panic(PSTR("Bad var table"));
|
||||
cliSerial->printf_P("Bad var table\n");
|
||||
hal.scheduler->panic("Bad var table");
|
||||
}
|
||||
|
||||
// disable centrifugal force correction, it will be enabled as part of the arming process
|
||||
|
@ -1160,17 +1160,17 @@ void Copter::load_parameters(void)
|
|||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||
cliSerial->printf_P("Firmware change: erasing EEPROM...\n");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println_P(PSTR("done."));
|
||||
cliSerial->println_P("done.");
|
||||
} else {
|
||||
uint32_t before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||
cliSerial->printf_P("load_all took %luus\n", micros() - before);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -610,7 +610,7 @@ bool Copter::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
// check if timer has run out
|
||||
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
||||
gcs_send_text_fmt(PSTR("Reached Command #%i"),cmd.index);
|
||||
gcs_send_text_fmt("Reached Command #%i",cmd.index);
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
|
@ -692,7 +692,7 @@ bool Copter::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
// check if timer has run out
|
||||
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
|
||||
gcs_send_text_fmt(PSTR("Reached Command #%i"),cmd.index);
|
||||
gcs_send_text_fmt("Reached Command #%i",cmd.index);
|
||||
return true;
|
||||
}else{
|
||||
return false;
|
||||
|
|
|
@ -37,7 +37,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
|
||||
// check compass is enabled
|
||||
if (!g.compass_enabled) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("compass disabled\n"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "compass disabled\n");
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
}
|
||||
|
@ -46,7 +46,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
compass.read();
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
if (!compass.healthy(i)) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("check compass"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "check compass");
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
// check if radio is calibrated
|
||||
pre_arm_rc_checks();
|
||||
if (!ap.pre_arm_rc_check) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("RC not calibrated"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "RC not calibrated");
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
}
|
||||
|
@ -63,14 +63,14 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
// check throttle is at zero
|
||||
read_radio();
|
||||
if (channel_throttle->control_in != 0) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("thr not zero"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "thr not zero");
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// check we are landed
|
||||
if (!ap.land_complete) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Not landed"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "Not landed");
|
||||
ap.compass_mot = false;
|
||||
return 1;
|
||||
}
|
||||
|
@ -95,13 +95,13 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
AP_Notify::flags.esc_calibration = true;
|
||||
|
||||
// warn user we are starting calibration
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("STARTING CALIBRATION"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "STARTING CALIBRATION");
|
||||
|
||||
// inform what type of compensation we are attempting
|
||||
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("CURRENT"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "CURRENT");
|
||||
} else{
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("THROTTLE"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "THROTTLE");
|
||||
}
|
||||
|
||||
// disable throttle and battery failsafe
|
||||
|
@ -245,10 +245,10 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||
}
|
||||
compass.save_motor_compensation();
|
||||
// display success message
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Calibration Successful!"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "Calibration Successful!");
|
||||
} else {
|
||||
// compensation vector never updated, report failure
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Failed!"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL, "Failed!");
|
||||
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
|
||||
}
|
||||
|
||||
|
|
|
@ -1007,19 +1007,19 @@ void Copter::autotune_update_gcs(uint8_t message_id)
|
|||
{
|
||||
switch (message_id) {
|
||||
case AUTOTUNE_MESSAGE_STARTED:
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("AutoTune: Started"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Started");
|
||||
break;
|
||||
case AUTOTUNE_MESSAGE_STOPPED:
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("AutoTune: Stopped"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Stopped");
|
||||
break;
|
||||
case AUTOTUNE_MESSAGE_SUCCESS:
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("AutoTune: Success"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Success");
|
||||
break;
|
||||
case AUTOTUNE_MESSAGE_FAILED:
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("AutoTune: Failed"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Failed");
|
||||
break;
|
||||
case AUTOTUNE_MESSAGE_SAVED_GAINS:
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("AutoTune: Saved Gains"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Saved Gains");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -47,7 +47,7 @@ void Copter::crash_check()
|
|||
// log an error in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH);
|
||||
// send message to gcs
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Crash: Disarming"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Crash: Disarming");
|
||||
// disarm motors
|
||||
init_disarm_motors();
|
||||
}
|
||||
|
@ -136,7 +136,7 @@ void Copter::parachute_check()
|
|||
void Copter::parachute_release()
|
||||
{
|
||||
// send message to gcs and dataflash
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Parachute: Released!"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Released!");
|
||||
Log_Write_Event(DATA_PARACHUTE_RELEASED);
|
||||
|
||||
// disarm motors
|
||||
|
@ -159,7 +159,7 @@ void Copter::parachute_manual_release()
|
|||
// do not release if we are landed or below the minimum altitude above home
|
||||
if (ap.land_complete) {
|
||||
// warn user of reason for failure
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Parachute: Landed"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Landed");
|
||||
// log an error in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_LANDED);
|
||||
return;
|
||||
|
@ -168,7 +168,7 @@ void Copter::parachute_manual_release()
|
|||
// do not release if we are landed or below the minimum altitude above home
|
||||
if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {
|
||||
// warn user of reason for failure
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Parachute: Too Low"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Too Low");
|
||||
// log an error in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_TOO_LOW);
|
||||
return;
|
||||
|
|
|
@ -60,7 +60,7 @@ void Copter::ekf_check()
|
|||
Log_Write_Error(ERROR_SUBSYSTEM_EKFCHECK, ERROR_CODE_EKFCHECK_BAD_VARIANCE);
|
||||
// send message to gcs
|
||||
if ((hal.scheduler->millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("EKF variance"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"EKF variance");
|
||||
ekf_check_state.last_warn_time = hal.scheduler->millis();
|
||||
}
|
||||
failsafe_ekf_event();
|
||||
|
|
|
@ -39,7 +39,7 @@ void Copter::esc_calibration_startup_check()
|
|||
// we will enter esc_calibrate mode on next reboot
|
||||
g.esc_calibrate.set_and_save(ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
|
||||
// send message to gcs
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("ESC Calibration: restart board"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: restart board");
|
||||
// turn on esc calibration notification
|
||||
AP_Notify::flags.esc_calibration = true;
|
||||
// block until we restart
|
||||
|
@ -85,7 +85,7 @@ void Copter::esc_calibration_passthrough()
|
|||
motors.set_update_rate(50);
|
||||
|
||||
// send message to GCS
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("ESC Calibration: passing pilot throttle to ESCs"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: passing pilot throttle to ESCs");
|
||||
|
||||
while(1) {
|
||||
// arm motors
|
||||
|
@ -115,7 +115,7 @@ void Copter::esc_calibration_auto()
|
|||
motors.set_update_rate(50);
|
||||
|
||||
// send message to GCS
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("ESC Calibration: auto calibration"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: auto calibration");
|
||||
|
||||
// arm and enable motors
|
||||
motors.armed(true);
|
||||
|
@ -131,7 +131,7 @@ void Copter::esc_calibration_auto()
|
|||
// wait for safety switch to be pressed
|
||||
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
if (!printed_msg) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("ESC Calibration: push safety switch"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: push safety switch");
|
||||
printed_msg = true;
|
||||
}
|
||||
delay(10);
|
||||
|
|
|
@ -159,7 +159,7 @@ void Copter::failsafe_battery_event(void)
|
|||
set_failsafe_battery(true);
|
||||
|
||||
// warn the ground station and log to dataflash
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Low Battery!"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Low Battery!");
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_BATT, ERROR_CODE_FAILSAFE_OCCURRED);
|
||||
|
||||
}
|
||||
|
|
|
@ -315,55 +315,55 @@ void Copter::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
{
|
||||
switch (mode) {
|
||||
case STABILIZE:
|
||||
port->print_P(PSTR("STABILIZE"));
|
||||
port->print_P("STABILIZE");
|
||||
break;
|
||||
case ACRO:
|
||||
port->print_P(PSTR("ACRO"));
|
||||
port->print_P("ACRO");
|
||||
break;
|
||||
case ALT_HOLD:
|
||||
port->print_P(PSTR("ALT_HOLD"));
|
||||
port->print_P("ALT_HOLD");
|
||||
break;
|
||||
case AUTO:
|
||||
port->print_P(PSTR("AUTO"));
|
||||
port->print_P("AUTO");
|
||||
break;
|
||||
case GUIDED:
|
||||
port->print_P(PSTR("GUIDED"));
|
||||
port->print_P("GUIDED");
|
||||
break;
|
||||
case LOITER:
|
||||
port->print_P(PSTR("LOITER"));
|
||||
port->print_P("LOITER");
|
||||
break;
|
||||
case RTL:
|
||||
port->print_P(PSTR("RTL"));
|
||||
port->print_P("RTL");
|
||||
break;
|
||||
case CIRCLE:
|
||||
port->print_P(PSTR("CIRCLE"));
|
||||
port->print_P("CIRCLE");
|
||||
break;
|
||||
case LAND:
|
||||
port->print_P(PSTR("LAND"));
|
||||
port->print_P("LAND");
|
||||
break;
|
||||
case OF_LOITER:
|
||||
port->print_P(PSTR("OF_LOITER"));
|
||||
port->print_P("OF_LOITER");
|
||||
break;
|
||||
case DRIFT:
|
||||
port->print_P(PSTR("DRIFT"));
|
||||
port->print_P("DRIFT");
|
||||
break;
|
||||
case SPORT:
|
||||
port->print_P(PSTR("SPORT"));
|
||||
port->print_P("SPORT");
|
||||
break;
|
||||
case FLIP:
|
||||
port->print_P(PSTR("FLIP"));
|
||||
port->print_P("FLIP");
|
||||
break;
|
||||
case AUTOTUNE:
|
||||
port->print_P(PSTR("AUTOTUNE"));
|
||||
port->print_P("AUTOTUNE");
|
||||
break;
|
||||
case POSHOLD:
|
||||
port->print_P(PSTR("POSHOLD"));
|
||||
port->print_P("POSHOLD");
|
||||
break;
|
||||
case BRAKE:
|
||||
port->print_P(PSTR("BRAKE"));
|
||||
port->print_P("BRAKE");
|
||||
break;
|
||||
default:
|
||||
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
||||
port->printf_P("Mode(%u)", (unsigned)mode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -74,19 +74,19 @@ bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
|
|||
// check rc has been calibrated
|
||||
pre_arm_rc_checks();
|
||||
if(check_rc && !ap.pre_arm_rc_check) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Motor Test: RC not calibrated"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,"Motor Test: RC not calibrated");
|
||||
return false;
|
||||
}
|
||||
|
||||
// ensure we are landed
|
||||
if (!ap.land_complete) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Motor Test: vehicle not landed"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,"Motor Test: vehicle not landed");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check if safety switch has been pushed
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Motor Test: Safety Switch"));
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(MAV_SEVERITY_CRITICAL,"Motor Test: Safety Switch");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -149,7 +149,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
|||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("ARMING MOTORS"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "ARMING MOTORS");
|
||||
#endif
|
||||
|
||||
// Remember Orientation
|
||||
|
@ -178,7 +178,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
|||
|
||||
// if we are using motor interlock switch and it's enabled, fail to arm
|
||||
if (ap.using_interlock && motors.get_interlock()){
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Motor Interlock Enabled"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
|
||||
AP_Notify::flags.armed = false;
|
||||
in_arm_motors = false;
|
||||
return false;
|
||||
|
@ -190,7 +190,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
|||
set_motor_emergency_stop(false);
|
||||
// if we are using motor Estop switch, it must not be in Estop position
|
||||
} else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Motor Emergency Stopped"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
|
||||
AP_Notify::flags.armed = false;
|
||||
in_arm_motors = false;
|
||||
return false;
|
||||
|
@ -246,7 +246,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// at the same time. This cannot be allowed.
|
||||
if (check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Interlock/E-Stop Conflict"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -258,7 +258,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
|
||||
if (ap.using_interlock && motors.get_interlock()){
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Motor Interlock Enabled"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -267,7 +267,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// and warn if it is
|
||||
if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Motor Emergency Stopped"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Motor Emergency Stopped");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -291,7 +291,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
pre_arm_rc_checks();
|
||||
if(!ap.pre_arm_rc_check) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: RC not calibrated"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -300,7 +300,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// barometer health check
|
||||
if(!barometer.all_healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Barometer not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Barometer not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -312,7 +312,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
if (using_baro_ref) {
|
||||
if (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Altitude disparity"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -324,7 +324,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check the primary compass is healthy
|
||||
if(!compass.healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -332,7 +332,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check compass learning is on or offsets have been set
|
||||
if(!compass.configured()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass not calibrated"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -341,7 +341,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
Vector3f offsets = compass.get_offsets();
|
||||
if(offsets.length() > COMPASS_OFFSETS_MAX) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass offsets too high"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -350,7 +350,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
float mag_field = compass.get_field().length();
|
||||
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check mag field"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -358,7 +358,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check all compasses point in roughly same direction
|
||||
if (!compass.consistent()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent compasses"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -374,7 +374,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check fence is initialised
|
||||
if(!fence.pre_arm_check()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: check fence"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: check fence");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -385,7 +385,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check accelerometers have been calibrated
|
||||
if(!ins.accel_calibrated_ok_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Accels not calibrated"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Accels not calibrated");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -393,7 +393,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check accels are healthy
|
||||
if(!ins.get_accel_health_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Accelerometers not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Accelerometers not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -416,7 +416,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
}
|
||||
if (vec_diff.length() > threshold) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent Accelerometers"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -426,7 +426,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check gyros are healthy
|
||||
if(!ins.get_gyro_health_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Gyros not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Gyros not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -438,7 +438,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
Vector3f vec_diff = ins.get_gyro(i) - ins.get_gyro();
|
||||
if (vec_diff.length() > PREARM_MAX_GYRO_VECTOR_DIFF) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent Gyros"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Gyros");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -448,7 +448,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// get ekf attitude (if bad, it's usually the gyro biases)
|
||||
if (!pre_arm_ekf_attitude_check()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: gyros still settling"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -459,7 +459,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
||||
if(hal.analogin->board_voltage() < BOARD_VOLTAGE_MIN || hal.analogin->board_voltage() > BOARD_VOLTAGE_MAX) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check Board Voltage"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -471,7 +471,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
||||
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check Battery"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check Battery");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -483,7 +483,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// ensure ch7 and ch8 have different functions
|
||||
if (check_duplicate_auxsw()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Duplicate Aux Switch Options"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -493,7 +493,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
|
||||
if (channel_throttle->radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check FS_THR_VALUE"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -502,7 +502,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// lean angle parameter check
|
||||
if (aparm.angle_max < 1000 || aparm.angle_max > 8000) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check ANGLE_MAX"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -510,7 +510,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// acro balance parameter check
|
||||
if ((g.acro_balance_roll > g.p_stabilize_roll.kP()) || (g.acro_balance_pitch > g.p_stabilize_pitch.kP())) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: ACRO_BAL_ROLL/PITCH"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -519,7 +519,7 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
// check range finder if optflow enabled
|
||||
if (optflow.enabled() && !sonar.pre_arm_check()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: check range finder"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: check range finder");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -538,9 +538,9 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
|
||||
if (display_failure) {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Collective below Failsafe"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
|
||||
#else
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Throttle below Failsafe"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Throttle below Failsafe");
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
|
@ -601,7 +601,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
|||
// always check if inertial nav has started and is ready
|
||||
if(!ahrs.healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Waiting for Nav Checks"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -627,9 +627,9 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
|||
if (display_failure) {
|
||||
const char *reason = ahrs.prearm_failure_reason();
|
||||
if (reason) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: %s"), reason);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Need 3D Fix"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix");
|
||||
}
|
||||
}
|
||||
AP_Notify::flags.pre_arm_gps_check = false;
|
||||
|
@ -643,7 +643,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
|||
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
|
||||
if (mag_variance.length() >= g.fs_ekf_thresh) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: EKF compass variance"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -651,7 +651,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
|||
// check home and EKF origin are not too far
|
||||
if (far_from_EKF_origin(ahrs.get_home())) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: EKF-home variance"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance");
|
||||
}
|
||||
AP_Notify::flags.pre_arm_gps_check = false;
|
||||
return false;
|
||||
|
@ -666,7 +666,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
|||
// warn about hdop separately - to prevent user confusion with no gps lock
|
||||
if (gps.get_hdop() > g.gps_hdop_good) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: High GPS HDOP"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP");
|
||||
}
|
||||
AP_Notify::flags.pre_arm_gps_check = false;
|
||||
return false;
|
||||
|
@ -700,20 +700,20 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
||||
if(!ins.get_accel_health_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Accelerometers not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if(!ins.get_gyro_health_all()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Gyros not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Gyros not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
// get ekf attitude (if bad, it's usually the gyro biases)
|
||||
if (!pre_arm_ekf_attitude_check()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: gyros still settling"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: gyros still settling");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -722,14 +722,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
// always check if inertial nav has started and is ready
|
||||
if(!ahrs.healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Waiting for Nav Checks"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
if(compass.is_calibrating()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Compass calibration running"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -737,7 +737,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
// always check if the current mode allows arming
|
||||
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Mode not armable"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -757,7 +757,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
// baro health check
|
||||
if (!barometer.all_healthy()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Barometer not healthy"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Barometer not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -768,7 +768,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
|
||||
if (using_baro_ref && (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM)) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Altitude disparity"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Altitude disparity");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -778,7 +778,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
// check vehicle is within fence
|
||||
if(!fence.pre_arm_check()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: check fence"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: check fence");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -788,7 +788,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
||||
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Leaning"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Leaning");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -798,7 +798,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
|
||||
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Check Battery"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Check Battery");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -810,9 +810,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
|
||||
if (display_failure) {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Collective below Failsafe"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
|
||||
#else
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Throttle below Failsafe"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle below Failsafe");
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
|
@ -824,9 +824,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if (channel_throttle->control_in > get_takeoff_trigger_throttle()) {
|
||||
if (display_failure) {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Collective too high"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
|
||||
#else
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Throttle too high"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
|
@ -835,9 +835,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) {
|
||||
if (display_failure) {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Collective too high"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
|
||||
#else
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Throttle too high"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
|
||||
#endif
|
||||
}
|
||||
return false;
|
||||
|
@ -848,7 +848,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
// check if safety switch has been pushed
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Safety Switch"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -866,7 +866,7 @@ void Copter::init_disarm_motors()
|
|||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("DISARMING MOTORS"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "DISARMING MOTORS");
|
||||
#endif
|
||||
|
||||
// save compass offsets learned by the EKF
|
||||
|
@ -936,7 +936,7 @@ void Copter::lost_vehicle_check()
|
|||
if (soundalarm_counter >= LOST_VEHICLE_DELAY) {
|
||||
if (AP_Notify::flags.vehicle_lost == false) {
|
||||
AP_Notify::flags.vehicle_lost = true;
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Locate Copter Alarm!"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Locate Copter Alarm!");
|
||||
}
|
||||
} else {
|
||||
soundalarm_counter++;
|
||||
|
|
|
@ -4,13 +4,13 @@
|
|||
|
||||
void Copter::init_barometer(bool full_calibration)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Calibrating barometer"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
|
||||
if (full_calibration) {
|
||||
barometer.calibrate();
|
||||
}else{
|
||||
barometer.update_calibration();
|
||||
}
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("barometer calibration complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
|
||||
}
|
||||
|
||||
// return barometric altitude in centimeters
|
||||
|
@ -87,7 +87,7 @@ void Copter::init_compass()
|
|||
{
|
||||
if (!compass.init() || !compass.read()) {
|
||||
// make sure we don't pass a broken compass to DCM
|
||||
cliSerial->println_P(PSTR("COMPASS INIT ERROR"));
|
||||
cliSerial->println_P("COMPASS INIT ERROR");
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -25,7 +25,7 @@ MENU(setup_menu, "setup", setup_menu_commands);
|
|||
int8_t Copter::setup_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
// Give the user some guidance
|
||||
cliSerial->printf_P(PSTR("Setup Mode\n\n\n"));
|
||||
cliSerial->printf_P("Setup Mode\n\n\n");
|
||||
|
||||
// Run the setup menu. When the menu exits, we will return to the main menu.
|
||||
setup_menu.run();
|
||||
|
@ -38,7 +38,7 @@ int8_t Copter::setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
int16_t c;
|
||||
|
||||
cliSerial->printf_P(PSTR("\n'Y' = factory reset, any other key to abort:\n"));
|
||||
cliSerial->printf_P("\n'Y' = factory reset, any other key to abort:\n");
|
||||
|
||||
do {
|
||||
c = cliSerial->read();
|
||||
|
@ -48,7 +48,7 @@ int8_t Copter::setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||
return(-1);
|
||||
|
||||
AP_Param::erase_all();
|
||||
cliSerial->printf_P(PSTR("\nReboot board"));
|
||||
cliSerial->printf_P("\nReboot board");
|
||||
|
||||
delay(1000);
|
||||
|
||||
|
@ -70,14 +70,14 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
if(argc!=3)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Invalid command. Usage: set <name> <value>\n"));
|
||||
cliSerial->printf_P("Invalid command. Usage: set <name> <value>\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
param = AP_Param::find(argv[1].str, &p_type);
|
||||
if(!param)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Param not found: %s\n"), argv[1].str);
|
||||
cliSerial->printf_P("Param not found: %s\n", argv[1].str);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -87,7 +87,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
value_int8 = (int8_t)(argv[2].i);
|
||||
if(argv[2].i!=value_int8)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Value out of range for type INT8\n"));
|
||||
cliSerial->printf_P("Value out of range for type INT8\n");
|
||||
return 0;
|
||||
}
|
||||
((AP_Int8*)param)->set_and_save(value_int8);
|
||||
|
@ -96,7 +96,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
value_int16 = (int16_t)(argv[2].i);
|
||||
if(argv[2].i!=value_int16)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Value out of range for type INT16\n"));
|
||||
cliSerial->printf_P("Value out of range for type INT16\n");
|
||||
return 0;
|
||||
}
|
||||
((AP_Int16*)param)->set_and_save(value_int16);
|
||||
|
@ -110,7 +110,7 @@ int8_t Copter::setup_set(uint8_t argc, const Menu::arg *argv)
|
|||
((AP_Float*)param)->set_and_save(argv[2].f);
|
||||
break;
|
||||
default:
|
||||
cliSerial->printf_P(PSTR("Cannot set parameter of type %d.\n"), p_type);
|
||||
cliSerial->printf_P("Cannot set parameter of type %d.\n", p_type);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -132,7 +132,7 @@ int8_t Copter::setup_show(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
if(!param)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Parameter not found: '%s'\n"), argv[1]);
|
||||
cliSerial->printf_P("Parameter not found: '%s'\n", argv[1]);
|
||||
return 0;
|
||||
}
|
||||
AP_Param::show(param, argv[1].str, type, cliSerial);
|
||||
|
@ -177,8 +177,8 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
|
||||
|
||||
if (argc < 2) {
|
||||
cliSerial->printf_P(PSTR("Pls provide Channel Mask\n"
|
||||
"\tusage: esc_calib 1010 - enables calibration for 2nd and 4th Motor\n"));
|
||||
cliSerial->printf_P("Pls provide Channel Mask\n"
|
||||
"\tusage: esc_calib 1010 - enables calibration for 2nd and 4th Motor\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -186,21 +186,21 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
|
||||
set_mask = strtol (argv[1].str, NULL, 2);
|
||||
if (set_mask == 0)
|
||||
cliSerial->printf_P(PSTR("no channels chosen"));
|
||||
//cliSerial->printf_P(PSTR("\n%d\n"),set_mask);
|
||||
cliSerial->printf_P("no channels chosen");
|
||||
//cliSerial->printf_P("\n%d\n",set_mask);
|
||||
set_mask<<=1;
|
||||
/* wait 50 ms */
|
||||
hal.scheduler->delay(50);
|
||||
|
||||
|
||||
cliSerial->printf_P(PSTR("\nATTENTION, please remove or fix propellers before starting calibration!\n"
|
||||
cliSerial->printf_P("\nATTENTION, please remove or fix propellers before starting calibration!\n"
|
||||
"\n"
|
||||
"Make sure\n"
|
||||
"\t - that the ESCs are not powered\n"
|
||||
"\t - that safety is off\n"
|
||||
"\t - that the controllers are stopped\n"
|
||||
"\n"
|
||||
"Do you want to start calibration now: y or n?\n"));
|
||||
"Do you want to start calibration now: y or n?\n");
|
||||
|
||||
/* wait for user input */
|
||||
while (1) {
|
||||
|
@ -210,11 +210,11 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
|
||||
cliSerial->printf_P("ESC calibration exited\n");
|
||||
return(0);
|
||||
|
||||
} else if (c == 'n' || c == 'N') {
|
||||
cliSerial->printf_P(PSTR("ESC calibration aborted\n"));
|
||||
cliSerial->printf_P("ESC calibration aborted\n");
|
||||
return(0);
|
||||
|
||||
}
|
||||
|
@ -231,14 +231,14 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
motors.armed(true);
|
||||
|
||||
|
||||
cliSerial->printf_P(PSTR("Outputs armed\n"));
|
||||
cliSerial->printf_P("Outputs armed\n");
|
||||
|
||||
|
||||
/* wait for user confirmation */
|
||||
cliSerial->printf_P(PSTR("\nHigh PWM set: %d\n"
|
||||
cliSerial->printf_P("\nHigh PWM set: %d\n"
|
||||
"\n"
|
||||
"Connect battery now and hit c+ENTER after the ESCs confirm the first calibration step\n"
|
||||
"\n"), pwm_high);
|
||||
"\n", pwm_high);
|
||||
|
||||
while (1) {
|
||||
/* set max PWM */
|
||||
|
@ -254,7 +254,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
|
||||
cliSerial->printf_P("ESC calibration exited\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -262,10 +262,10 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
hal.scheduler->delay(50);
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("Low PWM set: %d\n"
|
||||
cliSerial->printf_P("Low PWM set: %d\n"
|
||||
"\n"
|
||||
"Hit c+Enter when finished\n"
|
||||
"\n"), pwm_low);
|
||||
"\n", pwm_low);
|
||||
|
||||
while (1) {
|
||||
|
||||
|
@ -282,7 +282,7 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
break;
|
||||
|
||||
} else if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
cliSerial->printf_P(PSTR("ESC calibration exited\n"));
|
||||
cliSerial->printf_P("ESC calibration exited\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -293,9 +293,9 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
/* disarm */
|
||||
motors.armed(false);
|
||||
|
||||
cliSerial->printf_P(PSTR("Outputs disarmed\n"));
|
||||
cliSerial->printf_P("Outputs disarmed\n");
|
||||
|
||||
cliSerial->printf_P(PSTR("ESC calibration finished\n"));
|
||||
cliSerial->printf_P("ESC calibration finished\n");
|
||||
|
||||
return(0);
|
||||
}
|
||||
|
@ -308,35 +308,35 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
|||
|
||||
void Copter::report_batt_monitor()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\nBatt Mon:\n"));
|
||||
cliSerial->printf_P("\nBatt Mon:\n");
|
||||
print_divider();
|
||||
if (battery.num_instances() == 0) {
|
||||
print_enabled(false);
|
||||
} else if (!battery.has_current()) {
|
||||
cliSerial->printf_P(PSTR("volts"));
|
||||
cliSerial->printf_P("volts");
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("volts and cur"));
|
||||
cliSerial->printf_P("volts and cur");
|
||||
}
|
||||
print_blanks(2);
|
||||
}
|
||||
|
||||
void Copter::report_frame()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Frame\n"));
|
||||
cliSerial->printf_P("Frame\n");
|
||||
print_divider();
|
||||
|
||||
#if FRAME_CONFIG == QUAD_FRAME
|
||||
cliSerial->printf_P(PSTR("Quad frame\n"));
|
||||
cliSerial->printf_P("Quad frame\n");
|
||||
#elif FRAME_CONFIG == TRI_FRAME
|
||||
cliSerial->printf_P(PSTR("TRI frame\n"));
|
||||
cliSerial->printf_P("TRI frame\n");
|
||||
#elif FRAME_CONFIG == HEXA_FRAME
|
||||
cliSerial->printf_P(PSTR("Hexa frame\n"));
|
||||
cliSerial->printf_P("Hexa frame\n");
|
||||
#elif FRAME_CONFIG == Y6_FRAME
|
||||
cliSerial->printf_P(PSTR("Y6 frame\n"));
|
||||
cliSerial->printf_P("Y6 frame\n");
|
||||
#elif FRAME_CONFIG == OCTA_FRAME
|
||||
cliSerial->printf_P(PSTR("Octa frame\n"));
|
||||
cliSerial->printf_P("Octa frame\n");
|
||||
#elif FRAME_CONFIG == HELI_FRAME
|
||||
cliSerial->printf_P(PSTR("Heli frame\n"));
|
||||
cliSerial->printf_P("Heli frame\n");
|
||||
#endif
|
||||
|
||||
print_blanks(2);
|
||||
|
@ -344,7 +344,7 @@ void Copter::report_frame()
|
|||
|
||||
void Copter::report_radio()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Radio\n"));
|
||||
cliSerial->printf_P("Radio\n");
|
||||
print_divider();
|
||||
// radio
|
||||
print_radio_values();
|
||||
|
@ -353,7 +353,7 @@ void Copter::report_radio()
|
|||
|
||||
void Copter::report_ins()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("INS\n"));
|
||||
cliSerial->printf_P("INS\n");
|
||||
print_divider();
|
||||
|
||||
print_gyro_offsets();
|
||||
|
@ -363,7 +363,7 @@ void Copter::report_ins()
|
|||
|
||||
void Copter::report_flight_modes()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Flight modes\n"));
|
||||
cliSerial->printf_P("Flight modes\n");
|
||||
print_divider();
|
||||
|
||||
for(int16_t i = 0; i < 6; i++ ) {
|
||||
|
@ -375,7 +375,7 @@ void Copter::report_flight_modes()
|
|||
void Copter::report_optflow()
|
||||
{
|
||||
#if OPTFLOW == ENABLED
|
||||
cliSerial->printf_P(PSTR("OptFlow\n"));
|
||||
cliSerial->printf_P("OptFlow\n");
|
||||
print_divider();
|
||||
|
||||
print_enabled(optflow.enabled());
|
||||
|
@ -390,32 +390,32 @@ void Copter::report_optflow()
|
|||
|
||||
void Copter::print_radio_values()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("CH1: %d | %d\n"), (int)channel_roll->radio_min, (int)channel_roll->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH2: %d | %d\n"), (int)channel_pitch->radio_min, (int)channel_pitch->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH3: %d | %d\n"), (int)channel_throttle->radio_min, (int)channel_throttle->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH4: %d | %d\n"), (int)channel_yaw->radio_min, (int)channel_yaw->radio_max);
|
||||
cliSerial->printf_P(PSTR("CH5: %d | %d\n"), (int)g.rc_5.radio_min, (int)g.rc_5.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH6: %d | %d\n"), (int)g.rc_6.radio_min, (int)g.rc_6.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH7: %d | %d\n"), (int)g.rc_7.radio_min, (int)g.rc_7.radio_max);
|
||||
cliSerial->printf_P(PSTR("CH8: %d | %d\n"), (int)g.rc_8.radio_min, (int)g.rc_8.radio_max);
|
||||
cliSerial->printf_P("CH1: %d | %d\n", (int)channel_roll->radio_min, (int)channel_roll->radio_max);
|
||||
cliSerial->printf_P("CH2: %d | %d\n", (int)channel_pitch->radio_min, (int)channel_pitch->radio_max);
|
||||
cliSerial->printf_P("CH3: %d | %d\n", (int)channel_throttle->radio_min, (int)channel_throttle->radio_max);
|
||||
cliSerial->printf_P("CH4: %d | %d\n", (int)channel_yaw->radio_min, (int)channel_yaw->radio_max);
|
||||
cliSerial->printf_P("CH5: %d | %d\n", (int)g.rc_5.radio_min, (int)g.rc_5.radio_max);
|
||||
cliSerial->printf_P("CH6: %d | %d\n", (int)g.rc_6.radio_min, (int)g.rc_6.radio_max);
|
||||
cliSerial->printf_P("CH7: %d | %d\n", (int)g.rc_7.radio_min, (int)g.rc_7.radio_max);
|
||||
cliSerial->printf_P("CH8: %d | %d\n", (int)g.rc_8.radio_min, (int)g.rc_8.radio_max);
|
||||
}
|
||||
|
||||
void Copter::print_switch(uint8_t p, uint8_t m, bool b)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Pos %d:\t"),p);
|
||||
cliSerial->printf_P("Pos %d:\t",p);
|
||||
print_flight_mode(cliSerial, m);
|
||||
cliSerial->printf_P(PSTR(",\t\tSimple: "));
|
||||
cliSerial->printf_P(",\t\tSimple: ");
|
||||
if(b)
|
||||
cliSerial->printf_P(PSTR("ON\n"));
|
||||
cliSerial->printf_P("ON\n");
|
||||
else
|
||||
cliSerial->printf_P(PSTR("OFF\n"));
|
||||
cliSerial->printf_P("OFF\n");
|
||||
}
|
||||
|
||||
void Copter::print_accel_offsets_and_scaling(void)
|
||||
{
|
||||
const Vector3f &accel_offsets = ins.get_accel_offsets();
|
||||
const Vector3f &accel_scale = ins.get_accel_scale();
|
||||
cliSerial->printf_P(PSTR("A_off: %4.2f, %4.2f, %4.2f\nA_scale: %4.2f, %4.2f, %4.2f\n"),
|
||||
cliSerial->printf_P("A_off: %4.2f, %4.2f, %4.2f\nA_scale: %4.2f, %4.2f, %4.2f\n",
|
||||
(double)accel_offsets.x, // Pitch
|
||||
(double)accel_offsets.y, // Roll
|
||||
(double)accel_offsets.z, // YAW
|
||||
|
@ -427,7 +427,7 @@ void Copter::print_accel_offsets_and_scaling(void)
|
|||
void Copter::print_gyro_offsets(void)
|
||||
{
|
||||
const Vector3f &gyro_offsets = ins.get_gyro_offsets();
|
||||
cliSerial->printf_P(PSTR("G_off: %4.2f, %4.2f, %4.2f\n"),
|
||||
cliSerial->printf_P("G_off: %4.2f, %4.2f, %4.2f\n",
|
||||
(double)gyro_offsets.x,
|
||||
(double)gyro_offsets.y,
|
||||
(double)gyro_offsets.z);
|
||||
|
@ -438,13 +438,13 @@ void Copter::print_gyro_offsets(void)
|
|||
// report_compass - displays compass information. Also called by compassmot.pde
|
||||
void Copter::report_compass()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Compass\n"));
|
||||
cliSerial->printf_P("Compass\n");
|
||||
print_divider();
|
||||
|
||||
print_enabled(g.compass_enabled);
|
||||
|
||||
// mag declination
|
||||
cliSerial->printf_P(PSTR("Mag Dec: %4.4f\n"),
|
||||
cliSerial->printf_P("Mag Dec: %4.4f\n",
|
||||
(double)degrees(compass.get_declination()));
|
||||
|
||||
// mag offsets
|
||||
|
@ -452,7 +452,7 @@ void Copter::report_compass()
|
|||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
offsets = compass.get_offsets(i);
|
||||
// mag offsets
|
||||
cliSerial->printf_P(PSTR("Mag%d off: %4.4f, %4.4f, %4.4f\n"),
|
||||
cliSerial->printf_P("Mag%d off: %4.4f, %4.4f, %4.4f\n",
|
||||
(int)i,
|
||||
(double)offsets.x,
|
||||
(double)offsets.y,
|
||||
|
@ -460,20 +460,20 @@ void Copter::report_compass()
|
|||
}
|
||||
|
||||
// motor compensation
|
||||
cliSerial->print_P(PSTR("Motor Comp: "));
|
||||
cliSerial->print_P("Motor Comp: ");
|
||||
if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) {
|
||||
cliSerial->print_P(PSTR("Off\n"));
|
||||
cliSerial->print_P("Off\n");
|
||||
}else{
|
||||
if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) {
|
||||
cliSerial->print_P(PSTR("Throttle"));
|
||||
cliSerial->print_P("Throttle");
|
||||
}
|
||||
if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) {
|
||||
cliSerial->print_P(PSTR("Current"));
|
||||
cliSerial->print_P("Current");
|
||||
}
|
||||
Vector3f motor_compensation;
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
motor_compensation = compass.get_motor_compensation(i);
|
||||
cliSerial->printf_P(PSTR("\nComMot%d: %4.2f, %4.2f, %4.2f\n"),
|
||||
cliSerial->printf_P("\nComMot%d: %4.2f, %4.2f, %4.2f\n",
|
||||
(int)i,
|
||||
(double)motor_compensation.x,
|
||||
(double)motor_compensation.y,
|
||||
|
@ -494,7 +494,7 @@ void Copter::print_blanks(int16_t num)
|
|||
void Copter::print_divider(void)
|
||||
{
|
||||
for (int i = 0; i < 40; i++) {
|
||||
cliSerial->print_P(PSTR("-"));
|
||||
cliSerial->print_P("-");
|
||||
}
|
||||
cliSerial->println();
|
||||
}
|
||||
|
@ -502,15 +502,15 @@ void Copter::print_divider(void)
|
|||
void Copter::print_enabled(bool b)
|
||||
{
|
||||
if(b)
|
||||
cliSerial->print_P(PSTR("en"));
|
||||
cliSerial->print_P("en");
|
||||
else
|
||||
cliSerial->print_P(PSTR("dis"));
|
||||
cliSerial->print_P(PSTR("abled\n"));
|
||||
cliSerial->print_P("dis");
|
||||
cliSerial->print_P("abled\n");
|
||||
}
|
||||
|
||||
void Copter::report_version()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("FW Ver: %d\n"),(int)g.k_format_version);
|
||||
cliSerial->printf_P("FW Ver: %d\n",(int)g.k_format_version);
|
||||
print_divider();
|
||||
print_blanks(2);
|
||||
}
|
||||
|
|
|
@ -597,7 +597,7 @@ void Copter::save_trim()
|
|||
float pitch_trim = ToRad((float)channel_pitch->control_in/100.0f);
|
||||
ahrs.add_trim(roll_trim, pitch_trim);
|
||||
Log_Write_Event(DATA_SAVE_TRIM);
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Trim saved"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Trim saved");
|
||||
}
|
||||
|
||||
// auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions
|
||||
|
|
|
@ -14,12 +14,12 @@
|
|||
// This is the help function
|
||||
int8_t Copter::main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Commands:\n"
|
||||
cliSerial->printf_P("Commands:\n"
|
||||
" logs\n"
|
||||
" setup\n"
|
||||
" test\n"
|
||||
" reboot\n"
|
||||
"\n"));
|
||||
"\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -94,8 +94,8 @@ void Copter::init_ardupilot()
|
|||
// initialise serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n"),
|
||||
cliSerial->printf_P("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n",
|
||||
hal.util->available_memory());
|
||||
|
||||
//
|
||||
|
@ -219,7 +219,7 @@ void Copter::init_ardupilot()
|
|||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
if (g.cli_enabled) {
|
||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||
cliSerial->println_P(msg);
|
||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||
gcs[1].get_uart()->println_P(msg);
|
||||
|
@ -234,7 +234,7 @@ void Copter::init_ardupilot()
|
|||
while (barometer.get_last_update() == 0) {
|
||||
// the barometer begins updating when we get the first
|
||||
// HIL_STATE message
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Waiting for first HIL_STATE message"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
|
@ -282,7 +282,7 @@ void Copter::init_ardupilot()
|
|||
// init vehicle capabilties
|
||||
init_capabilities();
|
||||
|
||||
cliSerial->print_P(PSTR("\nReady to FLY "));
|
||||
cliSerial->print_P("\nReady to FLY ");
|
||||
|
||||
// flag that initialisation has completed
|
||||
ap.initialised = true;
|
||||
|
|
|
@ -44,9 +44,9 @@ int8_t Copter::test_baro(uint8_t argc, const Menu::arg *argv)
|
|||
read_barometer();
|
||||
|
||||
if (!barometer.healthy()) {
|
||||
cliSerial->println_P(PSTR("not healthy"));
|
||||
cliSerial->println_P("not healthy");
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||
cliSerial->printf_P("Alt: %0.2fm, Raw: %f Temperature: %.1f\n",
|
||||
(double)(baro_alt / 100.0f),
|
||||
(double)barometer.get_pressure(),
|
||||
(double)barometer.get_temperature());
|
||||
|
@ -65,13 +65,13 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
uint8_t medium_loopCounter = 0;
|
||||
|
||||
if (!g.compass_enabled) {
|
||||
cliSerial->printf_P(PSTR("Compass: "));
|
||||
cliSerial->printf_P("Compass: ");
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}
|
||||
|
||||
if (!compass.init()) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
cliSerial->println_P("Compass initialisation failed!");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -118,7 +118,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
if (compass.healthy()) {
|
||||
const Vector3f &mag_ofs = compass.get_offsets();
|
||||
const Vector3f &mag = compass.get_field();
|
||||
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||
cliSerial->printf_P("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n",
|
||||
(wrap_360_cd(ToDeg(heading) * 100)) /100,
|
||||
(double)mag.x,
|
||||
(double)mag.y,
|
||||
|
@ -127,7 +127,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
(double)mag_ofs.y,
|
||||
(double)mag_ofs.z);
|
||||
} else {
|
||||
cliSerial->println_P(PSTR("compass not healthy"));
|
||||
cliSerial->println_P("compass not healthy");
|
||||
}
|
||||
counter=0;
|
||||
}
|
||||
|
@ -139,7 +139,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
// save offsets. This allows you to get sane offset values using
|
||||
// the CLI before you go flying.
|
||||
cliSerial->println_P(PSTR("saving offsets"));
|
||||
cliSerial->println_P("saving offsets");
|
||||
compass.save_offsets();
|
||||
return (0);
|
||||
}
|
||||
|
@ -148,12 +148,12 @@ int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
Vector3f gyro, accel;
|
||||
print_hit_enter();
|
||||
cliSerial->printf_P(PSTR("INS\n"));
|
||||
cliSerial->printf_P("INS\n");
|
||||
delay(1000);
|
||||
|
||||
ahrs.init();
|
||||
ins.init(ins_sample_rate);
|
||||
cliSerial->printf_P(PSTR("...done\n"));
|
||||
cliSerial->printf_P("...done\n");
|
||||
|
||||
delay(50);
|
||||
|
||||
|
@ -164,7 +164,7 @@ int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
float test = accel.length() / GRAVITY_MSS;
|
||||
|
||||
cliSerial->printf_P(PSTR("a %7.4f %7.4f %7.4f g %7.4f %7.4f %7.4f t %7.4f \n"),
|
||||
cliSerial->printf_P("a %7.4f %7.4f %7.4f g %7.4f %7.4f %7.4f t %7.4f \n",
|
||||
(double)accel.x, (double)accel.y, (double)accel.z,
|
||||
(double)gyro.x, (double)gyro.y, (double)gyro.z,
|
||||
(double)test);
|
||||
|
@ -180,14 +180,14 @@ int8_t Copter::test_optflow(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
#if OPTFLOW == ENABLED
|
||||
if(optflow.enabled()) {
|
||||
cliSerial->printf_P(PSTR("dev id: %d\t"),(int)optflow.device_id());
|
||||
cliSerial->printf_P("dev id: %d\t",(int)optflow.device_id());
|
||||
print_hit_enter();
|
||||
|
||||
while(1) {
|
||||
delay(200);
|
||||
optflow.update();
|
||||
const Vector2f& flowRate = optflow.flowRate();
|
||||
cliSerial->printf_P(PSTR("flowX : %7.4f\t flowY : %7.4f\t flow qual : %d\n"),
|
||||
cliSerial->printf_P("flowX : %7.4f\t flowY : %7.4f\t flow qual : %d\n",
|
||||
(double)flowRate.x,
|
||||
(double)flowRate.y,
|
||||
(int)optflow.quality());
|
||||
|
@ -197,7 +197,7 @@ int8_t Copter::test_optflow(uint8_t argc, const Menu::arg *argv)
|
|||
}
|
||||
}
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("OptFlow: "));
|
||||
cliSerial->printf_P("OptFlow: ");
|
||||
print_enabled(false);
|
||||
}
|
||||
return (0);
|
||||
|
@ -212,14 +212,14 @@ int8_t Copter::test_relay(uint8_t argc, const Menu::arg *argv)
|
|||
delay(1000);
|
||||
|
||||
while(1) {
|
||||
cliSerial->printf_P(PSTR("Relay on\n"));
|
||||
cliSerial->printf_P("Relay on\n");
|
||||
relay.on(0);
|
||||
delay(3000);
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("Relay off\n"));
|
||||
cliSerial->printf_P("Relay off\n");
|
||||
relay.off(0);
|
||||
delay(3000);
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -248,15 +248,15 @@ int8_t Copter::test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
#if CONFIG_SONAR == ENABLED
|
||||
sonar.init();
|
||||
|
||||
cliSerial->printf_P(PSTR("RangeFinder: %d devices detected\n"), sonar.num_sensors());
|
||||
cliSerial->printf_P("RangeFinder: %d devices detected\n", sonar.num_sensors());
|
||||
|
||||
print_hit_enter();
|
||||
while(1) {
|
||||
delay(100);
|
||||
sonar.update();
|
||||
|
||||
cliSerial->printf_P(PSTR("Primary: status %d distance_cm %d \n"), (int)sonar.status(), sonar.distance_cm());
|
||||
cliSerial->printf_P(PSTR("All: device_0 type %d status %d distance_cm %d, device_1 type %d status %d distance_cm %d\n"),
|
||||
cliSerial->printf_P("Primary: status %d distance_cm %d \n", (int)sonar.status(), sonar.distance_cm());
|
||||
cliSerial->printf_P("All: device_0 type %d status %d distance_cm %d, device_1 type %d status %d distance_cm %d\n",
|
||||
(int)sonar._type[0], (int)sonar.status(0), sonar.distance_cm(0), (int)sonar._type[1], (int)sonar.status(1), sonar.distance_cm(1));
|
||||
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -270,7 +270,7 @@ int8_t Copter::test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Copter::print_hit_enter()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
cliSerial->printf_P("Hit Enter to exit.\n\n");
|
||||
}
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
|
|
@ -338,7 +338,7 @@ void Plane::one_second_loop()
|
|||
void Plane::log_perf_info()
|
||||
{
|
||||
if (scheduler.debug() != 0) {
|
||||
gcs_send_text_fmt(PSTR("G_Dt_max=%lu G_Dt_min=%lu\n"),
|
||||
gcs_send_text_fmt("G_Dt_max=%lu G_Dt_min=%lu\n",
|
||||
(unsigned long)G_Dt_max,
|
||||
(unsigned long)G_Dt_min);
|
||||
}
|
||||
|
@ -635,7 +635,7 @@ void Plane::update_flight_mode(void)
|
|||
if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) {
|
||||
if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) {
|
||||
auto_state.fbwa_tdrag_takeoff_mode = true;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("FBWA tdrag mode\n"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "FBWA tdrag mode\n");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -781,22 +781,22 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
|
|||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (g.fence_autoenable == 1) {
|
||||
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Disable fence failed (autodisable)"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Disable fence failed (autodisable)");
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Fence disabled (autodisable)"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence disabled (autodisable)");
|
||||
}
|
||||
} else if (g.fence_autoenable == 2) {
|
||||
if (! geofence_set_floor_enabled(false)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Disable fence floor failed (autodisable)"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Disable fence floor failed (autodisable)");
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Fence floor disabled (auto disable)"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence floor disabled (auto disable)");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
|
||||
gcs_send_text_fmt(PSTR("Landing aborted via throttle, climbing to %dm"), auto_state.takeoff_altitude_rel_cm/100);
|
||||
gcs_send_text_fmt("Landing aborted via throttle, climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
|
||||
break;
|
||||
|
||||
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
|
||||
|
|
|
@ -609,7 +609,7 @@ bool Plane::suppress_throttle(void)
|
|||
if (relative_altitude_abs_cm() >= 1000) {
|
||||
// we're more than 10m from the home altitude
|
||||
throttle_suppressed = false;
|
||||
gcs_send_text_fmt(PSTR("Throttle enabled - altitude %.2f"),
|
||||
gcs_send_text_fmt("Throttle enabled - altitude %.2f",
|
||||
(double)(relative_altitude_abs_cm()*0.01f));
|
||||
return false;
|
||||
}
|
||||
|
@ -620,7 +620,7 @@ bool Plane::suppress_throttle(void)
|
|||
// groundspeed with bad GPS reception
|
||||
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
|
||||
// we're moving at more than 5 m/s
|
||||
gcs_send_text_fmt(PSTR("Throttle enabled - speed %.2f airspeed %.2f"),
|
||||
gcs_send_text_fmt("Throttle enabled - speed %.2f airspeed %.2f",
|
||||
(double)gps.ground_speed(),
|
||||
(double)airspeed.get_airspeed());
|
||||
throttle_suppressed = false;
|
||||
|
@ -1061,7 +1061,7 @@ void Plane::set_servos(void)
|
|||
void Plane::demo_servos(uint8_t i)
|
||||
{
|
||||
while(i > 0) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Demo Servos!"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Demo Servos!");
|
||||
demoing_servos = true;
|
||||
servo_write(1, 1400);
|
||||
hal.scheduler->delay(400);
|
||||
|
|
|
@ -1135,7 +1135,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
||||
|
||||
// do command
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("command received: "));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"command received: ");
|
||||
|
||||
switch(packet.command) {
|
||||
|
||||
|
@ -1267,7 +1267,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
}
|
||||
else {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("Unsupported preflight calibration"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "Unsupported preflight calibration");
|
||||
}
|
||||
plane.in_calibration = false;
|
||||
break;
|
||||
|
@ -1386,9 +1386,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
plane.auto_state.commanded_go_around = true;
|
||||
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Go around command accepted."));
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Go around command accepted.");
|
||||
} else {
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Rejected go around command."));
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Rejected go around command.");
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -1412,7 +1412,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
if (! plane.geofence_set_floor_enabled(false)) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else {
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Fence floor disabled."));
|
||||
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Fence floor disabled.");
|
||||
}
|
||||
break;
|
||||
default:
|
||||
|
@ -1454,7 +1454,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
plane.Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
plane.gcs_send_text_fmt(PSTR("set home to %.6f %.6f at %um"),
|
||||
plane.gcs_send_text_fmt("set home to %.6f %.6f at %um",
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
(double)(new_home_loc.lng*1.0e-7f),
|
||||
(uint32_t)(new_home_loc.alt*0.01f));
|
||||
|
@ -1487,10 +1487,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
case PARACHUTE_RELEASE:
|
||||
// treat as a manual release which performs some additional check of altitude
|
||||
if (plane.parachute.released()) {
|
||||
plane.gcs_send_text_fmt(PSTR("Parachute already released"));
|
||||
plane.gcs_send_text_fmt("Parachute already released");
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else if (!plane.parachute.enabled()) {
|
||||
plane.gcs_send_text_fmt(PSTR("Parachute not enabled"));
|
||||
plane.gcs_send_text_fmt("Parachute not enabled");
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else {
|
||||
if (!plane.parachute_manual_release()) {
|
||||
|
@ -1550,10 +1550,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
// mark the firmware version in the tlog
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR(FIRMWARE_STRING));
|
||||
send_text_P(MAV_SEVERITY_WARNING, FIRMWARE_STRING);
|
||||
|
||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||
#endif
|
||||
handle_param_request_list(msg);
|
||||
break;
|
||||
|
@ -1612,11 +1612,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
mavlink_fence_point_t packet;
|
||||
mavlink_msg_fence_point_decode(msg, &packet);
|
||||
if (plane.g.fence_action != FENCE_ACTION_NONE) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("fencing must be disabled"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"fencing must be disabled");
|
||||
} else if (packet.count != plane.g.fence_total) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad fence point"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad fence point");
|
||||
} else if (fabsf(packet.lat) > 90.0f || fabsf(packet.lng) > 180.0f) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("invalid fence point, lat or lng too large"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"invalid fence point, lat or lng too large");
|
||||
} else {
|
||||
Vector2l point;
|
||||
point.x = packet.lat*1.0e7f;
|
||||
|
@ -1631,7 +1631,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
mavlink_fence_fetch_point_t packet;
|
||||
mavlink_msg_fence_fetch_point_decode(msg, &packet);
|
||||
if (packet.idx >= plane.g.fence_total) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad fence point"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad fence point");
|
||||
} else {
|
||||
Vector2l point = plane.get_fence_point_with_index(packet.idx);
|
||||
mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, plane.g.fence_total,
|
||||
|
@ -1648,12 +1648,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
if (packet.idx >= plane.rally.get_rally_total() ||
|
||||
packet.idx >= plane.rally.get_rally_max()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad rally point message ID"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad rally point message ID");
|
||||
break;
|
||||
}
|
||||
|
||||
if (packet.count != plane.rally.get_rally_total()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING,PSTR("bad rally point message count"));
|
||||
send_text_P(MAV_SEVERITY_WARNING,"bad rally point message count");
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1673,12 +1673,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
mavlink_rally_fetch_point_t packet;
|
||||
mavlink_msg_rally_fetch_point_decode(msg, &packet);
|
||||
if (packet.idx > plane.rally.get_rally_total()) {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("bad rally point index"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "bad rally point index");
|
||||
break;
|
||||
}
|
||||
RallyLocation rally_point;
|
||||
if (!plane.rally.get_rally_point_with_index(packet.idx, rally_point)) {
|
||||
send_text_P(MAV_SEVERITY_WARNING, PSTR("failed to set rally point"));
|
||||
send_text_P(MAV_SEVERITY_WARNING, "failed to set rally point");
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1896,7 +1896,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
||||
plane.Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||
plane.gcs_send_text_fmt(PSTR("set home to %.6f %.6f at %um"),
|
||||
plane.gcs_send_text_fmt("set home to %.6f %.6f at %um",
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
(double)(new_home_loc.lng*1.0e-7f),
|
||||
(uint32_t)(new_home_loc.alt*0.01f));
|
||||
|
@ -1932,7 +1932,7 @@ void Plane::mavlink_delay_cb()
|
|||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
last_5s = tnow;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Initialising APM..."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
|
||||
}
|
||||
check_usb_mux();
|
||||
|
||||
|
|
|
@ -24,16 +24,16 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&plane, &Plane::print_log
|
|||
|
||||
bool Plane::print_log_menu(void)
|
||||
{
|
||||
cliSerial->println_P(PSTR("logs enabled: "));
|
||||
cliSerial->println_P("logs enabled: ");
|
||||
|
||||
if (0 == g.log_bitmask) {
|
||||
cliSerial->println_P(PSTR("none"));
|
||||
cliSerial->println_P("none");
|
||||
}else{
|
||||
// Macro to make the following code a bit easier on the eye.
|
||||
// Pass it the capitalised name of the log option, as defined
|
||||
// in defines.h but without the LOG_ prefix. It will check for
|
||||
// the bit being set and print the name of the log option to suit.
|
||||
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(PSTR(" %S"), PSTR(# _s))
|
||||
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) cliSerial->printf_P(" %S", # _s)
|
||||
PLOG(ATTITUDE_FAST);
|
||||
PLOG(ATTITUDE_MED);
|
||||
PLOG(GPS);
|
||||
|
@ -71,11 +71,11 @@ int8_t Plane::dump_log(uint8_t argc, const Menu::arg *argv)
|
|||
DataFlash.DumpPageInfo(cliSerial);
|
||||
return(-1);
|
||||
} else if (dump_log_num <= 0) {
|
||||
cliSerial->printf_P(PSTR("dumping all\n"));
|
||||
cliSerial->printf_P("dumping all\n");
|
||||
Log_Read(0, 1, 0);
|
||||
return(-1);
|
||||
} else if ((argc != 2) || ((uint16_t)dump_log_num > DataFlash.get_num_logs())) {
|
||||
cliSerial->printf_P(PSTR("bad log number\n"));
|
||||
cliSerial->printf_P("bad log number\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -97,7 +97,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
uint32_t bits;
|
||||
|
||||
if (argc != 2) {
|
||||
cliSerial->printf_P(PSTR("missing log type\n"));
|
||||
cliSerial->printf_P("missing log type\n");
|
||||
return(-1);
|
||||
}
|
||||
|
||||
|
@ -109,10 +109,10 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
// that name as the argument to the command, and set the bit in
|
||||
// bits accordingly.
|
||||
//
|
||||
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
||||
if (!strcasecmp_P(argv[1].str, "all")) {
|
||||
bits = 0xFFFFFFFFUL;
|
||||
} else {
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(# _s))) bits |= MASK_LOG_ ## _s
|
||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, # _s)) bits |= MASK_LOG_ ## _s
|
||||
TARG(ATTITUDE_FAST);
|
||||
TARG(ATTITUDE_MED);
|
||||
TARG(GPS);
|
||||
|
@ -131,7 +131,7 @@ int8_t Plane::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||
#undef TARG
|
||||
}
|
||||
|
||||
if (!strcasecmp_P(argv[0].str, PSTR("enable"))) {
|
||||
if (!strcasecmp_P(argv[0].str, "enable")) {
|
||||
g.log_bitmask.set_and_save(g.log_bitmask | bits);
|
||||
}else{
|
||||
g.log_bitmask.set_and_save(g.log_bitmask & ~bits);
|
||||
|
@ -149,9 +149,9 @@ int8_t Plane::process_logs(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Plane::do_erase_logs(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Erasing logs"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Erasing logs");
|
||||
DataFlash.EraseAll();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Log erase complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Log erase complete");
|
||||
}
|
||||
|
||||
|
||||
|
@ -504,11 +504,11 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
|||
// Read the DataFlash.log memory : Packet Parser
|
||||
void Plane::Log_Read(uint16_t list_entry, int16_t start_page, int16_t end_page)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
|
||||
"\nFree RAM: %u\n"),
|
||||
cliSerial->printf_P("\n" FIRMWARE_STRING
|
||||
"\nFree RAM: %u\n",
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
cliSerial->println_P(PSTR(HAL_BOARD_NAME));
|
||||
cliSerial->println_P(HAL_BOARD_NAME);
|
||||
|
||||
DataFlash.LogReadProcess(list_entry, start_page, end_page,
|
||||
FUNCTOR_BIND_MEMBER(&Plane::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),
|
||||
|
@ -541,12 +541,12 @@ void Plane::log_init(void)
|
|||
{
|
||||
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
if (!DataFlash.CardInserted()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("No dataflash card inserted"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "No dataflash card inserted");
|
||||
g.log_bitmask.set(0);
|
||||
} else if (DataFlash.NeedPrep()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Preparing log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Preparing log system");
|
||||
DataFlash.Prep();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Prepared log system"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Prepared log system");
|
||||
for (uint8_t i=0; i<num_gcs; i++) {
|
||||
gcs[i].reset_cli_timeout();
|
||||
}
|
||||
|
|
|
@ -1259,24 +1259,24 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
|
|||
void Plane::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
cliSerial->printf_P(PSTR("Bad parameter table\n"));
|
||||
hal.scheduler->panic(PSTR("Bad parameter table"));
|
||||
cliSerial->printf_P("Bad parameter table\n");
|
||||
hal.scheduler->panic("Bad parameter table");
|
||||
}
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
cliSerial->printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||
cliSerial->printf_P("Firmware change: erasing EEPROM...\n");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println_P(PSTR("done."));
|
||||
cliSerial->println_P("done.");
|
||||
} else {
|
||||
uint32_t before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
cliSerial->printf_P(PSTR("load_all took %luus\n"), micros() - before);
|
||||
cliSerial->printf_P("load_all took %luus\n", micros() - before);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -578,7 +578,7 @@ void Plane::rangefinder_height_update(void)
|
|||
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH &&
|
||||
g.rangefinder_landing) {
|
||||
rangefinder_state.in_use = true;
|
||||
gcs_send_text_fmt(PSTR("Rangefinder engaged at %.2fm"), height_estimate);
|
||||
gcs_send_text_fmt("Rangefinder engaged at %.2fm", height_estimate);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
|
@ -610,7 +610,7 @@ void Plane::rangefinder_height_update(void)
|
|||
if (fabsf(rangefinder_state.correction - rangefinder_state.initial_correction) > 30) {
|
||||
// the correction has changed by more than 30m, reset use of Lidar. We may have a bad lidar
|
||||
if (rangefinder_state.in_use) {
|
||||
gcs_send_text_fmt(PSTR("Rangefinder disengaged at %.2fm"), height_estimate);
|
||||
gcs_send_text_fmt("Rangefinder disengaged at %.2fm", height_estimate);
|
||||
}
|
||||
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
|
||||
}
|
||||
|
|
|
@ -32,21 +32,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
|||
|
||||
if (plane.g.roll_limit_cd < 300) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_ROLL_CD too small (%u)"), plane.g.roll_limit_cd);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.g.roll_limit_cd);
|
||||
}
|
||||
ret = false;
|
||||
}
|
||||
|
||||
if (plane.aparm.pitch_limit_max_cd < 300) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_PITCH_MAX too small (%u)"), plane.aparm.pitch_limit_max_cd);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MAX too small (%u)", plane.aparm.pitch_limit_max_cd);
|
||||
}
|
||||
ret = false;
|
||||
}
|
||||
|
||||
if (plane.aparm.pitch_limit_min_cd > -300) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_PITCH_MIN too large (%u)"), plane.aparm.pitch_limit_min_cd);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MIN too large (%u)", plane.aparm.pitch_limit_min_cd);
|
||||
}
|
||||
ret = false;
|
||||
}
|
||||
|
@ -56,7 +56,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
|||
plane.g.throttle_fs_value <
|
||||
plane.channel_throttle->radio_max) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: invalid THR_FS_VALUE for rev throttle"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: invalid THR_FS_VALUE for rev throttle");
|
||||
}
|
||||
ret = false;
|
||||
}
|
||||
|
@ -78,9 +78,9 @@ bool AP_Arming_Plane::ins_checks(bool report)
|
|||
if (report) {
|
||||
const char *reason = ahrs.prearm_failure_reason();
|
||||
if (reason) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: %s"), reason);
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
|
||||
} else {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: AHRS not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: AHRS not healthy");
|
||||
}
|
||||
}
|
||||
return false;
|
||||
|
|
|
@ -52,7 +52,7 @@ void Plane::set_next_WP(const struct Location &loc)
|
|||
// location as the previous waypoint, to prevent immediately
|
||||
// considering the waypoint complete
|
||||
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Resetting prev_WP"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Resetting prev_WP");
|
||||
prev_WP_loc = current_loc;
|
||||
}
|
||||
|
||||
|
@ -100,14 +100,14 @@ void Plane::set_guided_WP(void)
|
|||
// -------------------------------
|
||||
void Plane::init_home()
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("init home"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "init home");
|
||||
|
||||
ahrs.set_home(gps.location());
|
||||
home_is_set = HOME_SET_NOT_LOCKED;
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(gps.location());
|
||||
|
||||
gcs_send_text_fmt(PSTR("gps alt: %lu"), (unsigned long)home.alt);
|
||||
gcs_send_text_fmt("gps alt: %lu", (unsigned long)home.alt);
|
||||
|
||||
// Save Home to EEPROM
|
||||
mission.write_home_to_storage();
|
||||
|
|
|
@ -31,9 +31,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
// once landed, post some landing statistics to the GCS
|
||||
auto_state.post_landing_stats = false;
|
||||
|
||||
gcs_send_text_fmt(PSTR("Executing nav command ID #%i"),cmd.id);
|
||||
gcs_send_text_fmt("Executing nav command ID #%i",cmd.id);
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Executing command ID #%i"),cmd.id);
|
||||
gcs_send_text_fmt("Executing command ID #%i",cmd.id);
|
||||
}
|
||||
|
||||
switch(cmd.id) {
|
||||
|
@ -124,7 +124,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
case MAV_CMD_DO_INVERTED_FLIGHT:
|
||||
if (cmd.p1 == 0 || cmd.p1 == 1) {
|
||||
auto_state.inverted_flight = (bool)cmd.p1;
|
||||
gcs_send_text_fmt(PSTR("Set inverted %u"), cmd.p1);
|
||||
gcs_send_text_fmt("Set inverted %u", cmd.p1);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -137,15 +137,15 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (cmd.p1 != 2) {
|
||||
if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) {
|
||||
gcs_send_text_fmt(PSTR("Unable to set fence enabled state to %u"), cmd.p1);
|
||||
gcs_send_text_fmt("Unable to set fence enabled state to %u", cmd.p1);
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Set fence enabled state to %u"), cmd.p1);
|
||||
gcs_send_text_fmt("Set fence enabled state to %u", cmd.p1);
|
||||
}
|
||||
} else { //commanding to only disable floor
|
||||
if (! geofence_set_floor_enabled(false)) {
|
||||
gcs_send_text_fmt(PSTR("Unabled to disable fence floor.\n"));
|
||||
gcs_send_text_fmt("Unabled to disable fence floor.\n");
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Fence floor disabled.\n"));
|
||||
gcs_send_text_fmt("Fence floor disabled.\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -291,9 +291,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
|||
default:
|
||||
// error message
|
||||
if (AP_Mission::is_nav_cmd(cmd)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("verify_nav: Invalid or no current Nav cmd"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_nav: Invalid or no current Nav cmd");
|
||||
}else{
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("verify_conditon: Invalid or no current Condition cmd"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_conditon: Invalid or no current Condition cmd");
|
||||
}
|
||||
// return true so that we do not get stuck at this command
|
||||
return true;
|
||||
|
@ -492,7 +492,7 @@ bool Plane::verify_takeoff()
|
|||
float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01f)) - steer_state.locked_course_err;
|
||||
takeoff_course = wrap_PI(takeoff_course);
|
||||
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
|
||||
gcs_send_text_fmt(PSTR("Holding course %ld at %.1fm/s (%.1f)"),
|
||||
gcs_send_text_fmt("Holding course %ld at %.1fm/s (%.1f)",
|
||||
steer_state.hold_course_cd,
|
||||
(double)gps.ground_speed(),
|
||||
(double)degrees(steer_state.locked_course_err));
|
||||
|
@ -509,7 +509,7 @@ bool Plane::verify_takeoff()
|
|||
// see if we have reached takeoff altitude
|
||||
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
|
||||
if (relative_alt_cm > auto_state.takeoff_altitude_rel_cm) {
|
||||
gcs_send_text_fmt(PSTR("Takeoff complete at %.2fm"),
|
||||
gcs_send_text_fmt("Takeoff complete at %.2fm",
|
||||
(double)(relative_alt_cm*0.01f));
|
||||
steer_state.hold_course_cd = -1;
|
||||
auto_state.takeoff_complete = true;
|
||||
|
@ -518,9 +518,9 @@ bool Plane::verify_takeoff()
|
|||
#if GEOFENCE_ENABLED == ENABLED
|
||||
if (g.fence_autoenable > 0) {
|
||||
if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Enable fence failed (cannot autoenable"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Enable fence failed (cannot autoenable");
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Fence enabled. (autoenabled)"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence enabled. (autoenabled)");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -565,7 +565,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
}
|
||||
|
||||
if (auto_state.wp_distance <= acceptance_distance) {
|
||||
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
|
||||
gcs_send_text_fmt("Reached Waypoint #%i dist %um",
|
||||
(unsigned)mission.get_current_nav_cmd().index,
|
||||
(unsigned)get_distance(current_loc, next_WP_loc));
|
||||
return true;
|
||||
|
@ -573,7 +573,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
// have we flown past the waypoint?
|
||||
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
||||
gcs_send_text_fmt(PSTR("Passed Waypoint #%i dist %um"),
|
||||
gcs_send_text_fmt("Passed Waypoint #%i dist %um",
|
||||
(unsigned)mission.get_current_nav_cmd().index,
|
||||
(unsigned)get_distance(current_loc, next_WP_loc));
|
||||
return true;
|
||||
|
@ -597,7 +597,7 @@ bool Plane::verify_loiter_time()
|
|||
loiter.start_time_ms = millis();
|
||||
}
|
||||
} else if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("verify_nav: LOITER time complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"verify_nav: LOITER time complete");
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -608,7 +608,7 @@ bool Plane::verify_loiter_turns()
|
|||
update_loiter();
|
||||
if (loiter.sum_cd > loiter.total_cd) {
|
||||
loiter.total_cd = 0;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("verify_nav: LOITER orbits complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"verify_nav: LOITER orbits complete");
|
||||
// clear the command queue;
|
||||
return true;
|
||||
}
|
||||
|
@ -692,7 +692,7 @@ bool Plane::verify_RTL()
|
|||
update_loiter();
|
||||
if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) ||
|
||||
nav_controller->reached_loiter_target()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Reached home"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached home");
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
|
@ -742,11 +742,11 @@ bool Plane::verify_continue_and_change_alt()
|
|||
bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Reached altitude"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached altitude");
|
||||
return true;
|
||||
}
|
||||
if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
|
||||
gcs_send_text_fmt(PSTR("Reached descent rate %.1f m/s"), (double)auto_state.sink_rate);
|
||||
gcs_send_text_fmt("Reached descent rate %.1f m/s", (double)auto_state.sink_rate);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -852,17 +852,17 @@ void Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
|||
case 0: // Airspeed
|
||||
if (cmd.content.speed.target_ms > 0) {
|
||||
g.airspeed_cruise_cm.set(cmd.content.speed.target_ms * 100);
|
||||
gcs_send_text_fmt(PSTR("Set airspeed %u m/s"), (unsigned)cmd.content.speed.target_ms);
|
||||
gcs_send_text_fmt("Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms);
|
||||
}
|
||||
break;
|
||||
case 1: // Ground speed
|
||||
gcs_send_text_fmt(PSTR("Set groundspeed %u"), (unsigned)cmd.content.speed.target_ms);
|
||||
gcs_send_text_fmt("Set groundspeed %u", (unsigned)cmd.content.speed.target_ms);
|
||||
g.min_gndspeed_cm.set(cmd.content.speed.target_ms * 100);
|
||||
break;
|
||||
}
|
||||
|
||||
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
|
||||
gcs_send_text_fmt(PSTR("Set throttle %u"), (unsigned)cmd.content.speed.throttle_pct);
|
||||
gcs_send_text_fmt("Set throttle %u", (unsigned)cmd.content.speed.throttle_pct);
|
||||
aparm.throttle_cruise.set(cmd.content.speed.throttle_pct);
|
||||
}
|
||||
}
|
||||
|
@ -980,7 +980,7 @@ bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
|
|||
void Plane::exit_mission_callback()
|
||||
{
|
||||
if (control_mode == AUTO) {
|
||||
gcs_send_text_fmt(PSTR("Returning to Home"));
|
||||
gcs_send_text_fmt("Returning to Home");
|
||||
memset(&auto_rtl_command, 0, sizeof(auto_rtl_command));
|
||||
auto_rtl_command.content.location =
|
||||
rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude());
|
||||
|
|
|
@ -77,17 +77,17 @@ void Plane::read_control_switch()
|
|||
if (hal.util->get_soft_armed() || setup_failsafe_mixing()) {
|
||||
px4io_override_enabled = true;
|
||||
// disable output channels to force PX4IO override
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4IO Override enabled"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override enabled");
|
||||
} else {
|
||||
// we'll try again next loop. The PX4IO code sometimes
|
||||
// rejects a mixer, probably due to it being busy in
|
||||
// some way?
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4IO Override enable failed"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override enable failed");
|
||||
}
|
||||
} else if (!override && px4io_override_enabled) {
|
||||
px4io_override_enabled = false;
|
||||
RC_Channel_aux::enable_aux_servos();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4IO Override disabled"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override disabled");
|
||||
}
|
||||
if (px4io_override_enabled &&
|
||||
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED) {
|
||||
|
|
|
@ -7,7 +7,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
|
|||
// This is how to handle a short loss of control signal failsafe.
|
||||
failsafe.state = fstype;
|
||||
failsafe.ch3_timer_ms = millis();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Failsafe - Short event on, "));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Short event on, ");
|
||||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
|
@ -46,13 +46,13 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
|
|||
default:
|
||||
break;
|
||||
}
|
||||
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
||||
gcs_send_text_fmt("flight mode = %u", (unsigned)control_mode);
|
||||
}
|
||||
|
||||
void Plane::failsafe_long_on_event(enum failsafe_state fstype)
|
||||
{
|
||||
// This is how to handle a long loss of control signal failsafe.
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Failsafe - Long event on, "));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Long event on, ");
|
||||
// If the GCS is locked up we allow control to revert to RC
|
||||
hal.rcin->clear_overrides();
|
||||
failsafe.state = fstype;
|
||||
|
@ -89,15 +89,15 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype)
|
|||
break;
|
||||
}
|
||||
if (fstype == FAILSAFE_GCS) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("No GCS heartbeat."));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "No GCS heartbeat.");
|
||||
}
|
||||
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
||||
gcs_send_text_fmt("flight mode = %u", (unsigned)control_mode);
|
||||
}
|
||||
|
||||
void Plane::failsafe_short_off_event()
|
||||
{
|
||||
// We're back in radio contact
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Failsafe - Short event off"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Short event off");
|
||||
failsafe.state = FAILSAFE_NONE;
|
||||
|
||||
// re-read the switch so we can return to our preferred mode
|
||||
|
@ -113,7 +113,7 @@ void Plane::low_battery_event(void)
|
|||
if (failsafe.low_battery) {
|
||||
return;
|
||||
}
|
||||
gcs_send_text_fmt(PSTR("Low Battery %.2fV Used %.0f mAh"),
|
||||
gcs_send_text_fmt("Low Battery %.2fV Used %.0f mAh",
|
||||
(double)battery.voltage(), (double)battery.current_total_mah());
|
||||
if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
|
||||
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||
|
|
|
@ -137,13 +137,13 @@ void Plane::geofence_load(void)
|
|||
geofence_state->boundary_uptodate = true;
|
||||
geofence_state->fence_triggered = false;
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("geo-fence loaded"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence loaded");
|
||||
gcs_send_message(MSG_FENCE_STATUS);
|
||||
return;
|
||||
|
||||
failed:
|
||||
g.fence_action.set(FENCE_ACTION_NONE);
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("geo-fence setup error"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"geo-fence setup error");
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -335,7 +335,7 @@ void Plane::geofence_check(bool altitude_check_only)
|
|||
if (geofence_state->fence_triggered && !altitude_check_only) {
|
||||
// we have moved back inside the fence
|
||||
geofence_state->fence_triggered = false;
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("geo-fence OK"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence OK");
|
||||
#if FENCE_TRIGGERED_PIN > 0
|
||||
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
|
||||
|
@ -365,7 +365,7 @@ void Plane::geofence_check(bool altitude_check_only)
|
|||
hal.gpio->write(FENCE_TRIGGERED_PIN, 1);
|
||||
#endif
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("geo-fence triggered"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence triggered");
|
||||
gcs_send_message(MSG_FENCE_STATUS);
|
||||
|
||||
// see what action the user wants
|
||||
|
|
|
@ -224,9 +224,9 @@ void Plane::crash_detection_update(void)
|
|||
|
||||
if (g.crash_detection_enable == CRASH_DETECT_ACTION_BITMASK_DISABLED) {
|
||||
if (crashed_near_land_waypoint) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Hard Landing Detected - no action taken"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken");
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Crash Detected - no action taken"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Crash Detected - no action taken");
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
@ -235,9 +235,9 @@ void Plane::crash_detection_update(void)
|
|||
}
|
||||
auto_state.land_complete = true;
|
||||
if (crashed_near_land_waypoint) {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Hard Landing Detected"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Hard Landing Detected");
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Crash Detected"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Crash Detected");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -74,9 +74,9 @@ bool Plane::verify_land()
|
|||
if (!auto_state.land_complete) {
|
||||
auto_state.post_landing_stats = true;
|
||||
if (!is_flying() && (millis()-auto_state.last_flying_ms) > 3000) {
|
||||
gcs_send_text_fmt(PSTR("Flare crash detected: speed=%.1f"), (double)gps.ground_speed());
|
||||
gcs_send_text_fmt("Flare crash detected: speed=%.1f", (double)gps.ground_speed());
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Flare %.1fm sink=%.2f speed=%.1f dist=%.1f"),
|
||||
gcs_send_text_fmt("Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
|
||||
(double)height, (double)auto_state.sink_rate,
|
||||
(double)gps.ground_speed(),
|
||||
(double)get_distance(current_loc, next_WP_loc));
|
||||
|
@ -110,7 +110,7 @@ bool Plane::verify_land()
|
|||
// this is done before disarm_if_autoland_complete() so that it happens on the next loop after the disarm
|
||||
if (auto_state.post_landing_stats && !arming.is_armed()) {
|
||||
auto_state.post_landing_stats = false;
|
||||
gcs_send_text_fmt(PSTR("Distance from LAND point=%.2fm"), (double)get_distance(current_loc, next_WP_loc));
|
||||
gcs_send_text_fmt("Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
|
||||
}
|
||||
|
||||
// check if we should auto-disarm after a confirmed landing
|
||||
|
@ -139,7 +139,7 @@ void Plane::disarm_if_autoland_complete()
|
|||
/* we have auto disarm enabled. See if enough time has passed */
|
||||
if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
|
||||
if (disarm_motors()) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Auto-Disarmed"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Auto-Disarmed");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -260,14 +260,14 @@ bool Plane::restart_landing_sequence()
|
|||
mission.set_current_cmd(current_index+1))
|
||||
{
|
||||
// if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it
|
||||
gcs_send_text_fmt(PSTR("Restarted landing sequence climbing to %dm"), cmd.content.location.alt/100);
|
||||
gcs_send_text_fmt("Restarted landing sequence climbing to %dm", cmd.content.location.alt/100);
|
||||
success = true;
|
||||
}
|
||||
else if (do_land_start_index != 0 &&
|
||||
mission.set_current_cmd(do_land_start_index))
|
||||
{
|
||||
// look for a DO_LAND_START and use that index
|
||||
gcs_send_text_fmt(PSTR("Restarted landing via DO_LAND_START: %d"),do_land_start_index);
|
||||
gcs_send_text_fmt("Restarted landing via DO_LAND_START: %d",do_land_start_index);
|
||||
success = true;
|
||||
}
|
||||
else if (prev_cmd_with_wp_index != AP_MISSION_CMD_INDEX_NONE &&
|
||||
|
@ -275,10 +275,10 @@ bool Plane::restart_landing_sequence()
|
|||
{
|
||||
// if a suitable navigation waypoint was just executed, one that contains lat/lng/alt, then
|
||||
// repeat that cmd to restart the landing from the top of approach to repeat intended glide slope
|
||||
gcs_send_text_fmt(PSTR("Restarted landing sequence at waypoint %d"), prev_cmd_with_wp_index);
|
||||
gcs_send_text_fmt("Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
|
||||
success = true;
|
||||
} else {
|
||||
gcs_send_text_fmt(PSTR("Unable to restart landing sequence!"));
|
||||
gcs_send_text_fmt("Unable to restart landing sequence!");
|
||||
success = false;
|
||||
}
|
||||
return success;
|
||||
|
@ -301,12 +301,12 @@ bool Plane::jump_to_landing_sequence(void)
|
|||
mission.resume();
|
||||
}
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Landing sequence begun."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Landing sequence begun.");
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, PSTR("Unable to start landing sequence."));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Unable to start landing sequence.");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@ void Plane::parachute_release()
|
|||
}
|
||||
|
||||
// send message to gcs and dataflash
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Parachute: Released"));
|
||||
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Released");
|
||||
|
||||
// release parachute
|
||||
parachute.release();
|
||||
|
@ -42,12 +42,12 @@ bool Plane::parachute_manual_release()
|
|||
// do not release if vehicle is not flying
|
||||
if (!is_flying()) {
|
||||
// warn user of reason for failure
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Parachute: not flying"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"Parachute: not flying");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (relative_altitude() < parachute.alt_min()) {
|
||||
gcs_send_text_fmt(PSTR("Parachute: too low"));
|
||||
gcs_send_text_fmt("Parachute: too low");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -239,7 +239,7 @@ void Plane::control_failsafe(uint16_t pwm)
|
|||
// throttle has dropped below the mark
|
||||
failsafe.ch3_counter++;
|
||||
if (failsafe.ch3_counter == 10) {
|
||||
gcs_send_text_fmt(PSTR("MSG FS ON %u"), (unsigned)pwm);
|
||||
gcs_send_text_fmt("MSG FS ON %u", (unsigned)pwm);
|
||||
failsafe.ch3_failsafe = true;
|
||||
AP_Notify::flags.failsafe_radio = true;
|
||||
}
|
||||
|
@ -255,7 +255,7 @@ void Plane::control_failsafe(uint16_t pwm)
|
|||
failsafe.ch3_counter = 3;
|
||||
}
|
||||
if (failsafe.ch3_counter == 1) {
|
||||
gcs_send_text_fmt(PSTR("MSG FS OFF %u"), (unsigned)pwm);
|
||||
gcs_send_text_fmt("MSG FS OFF %u", (unsigned)pwm);
|
||||
} else if(failsafe.ch3_counter == 0) {
|
||||
failsafe.ch3_failsafe = false;
|
||||
AP_Notify::flags.failsafe_radio = false;
|
||||
|
|
|
@ -5,10 +5,10 @@
|
|||
|
||||
void Plane::init_barometer(void)
|
||||
{
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Calibrating barometer"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
|
||||
barometer.calibrate();
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("barometer calibration complete"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
|
||||
}
|
||||
|
||||
void Plane::init_rangefinder(void)
|
||||
|
@ -75,7 +75,7 @@ void Plane::zero_airspeed(bool in_startup)
|
|||
read_airspeed();
|
||||
// update barometric calibration with new airspeed supplied temperature
|
||||
barometer.update_calibration();
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("zero airspeed calibrated"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"zero airspeed calibrated");
|
||||
}
|
||||
|
||||
// read_battery - reads battery voltage and current and invokes failsafe
|
||||
|
|
|
@ -19,12 +19,12 @@ MENU(setup_menu, "setup", setup_menu_commands);
|
|||
int8_t Plane::setup_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
// Give the user some guidance
|
||||
cliSerial->printf_P(PSTR("Setup Mode\n"
|
||||
cliSerial->printf_P("Setup Mode\n"
|
||||
"\n"
|
||||
"IMPORTANT: if you have not previously set this system up, use the\n"
|
||||
"'reset' command to initialize the EEPROM to sensible default values\n"
|
||||
"and then the 'radio' command to configure for your radio.\n"
|
||||
"\n"));
|
||||
"\n");
|
||||
|
||||
// Run the setup menu. When the menu exits, we will return to the main menu.
|
||||
setup_menu.run();
|
||||
|
@ -37,7 +37,7 @@ int8_t Plane::setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
int c;
|
||||
|
||||
cliSerial->printf_P(PSTR("\nType 'Y' and hit Enter to perform factory reset, any other key to abort: "));
|
||||
cliSerial->printf_P("\nType 'Y' and hit Enter to perform factory reset, any other key to abort: ");
|
||||
|
||||
do {
|
||||
c = cliSerial->read();
|
||||
|
@ -46,7 +46,7 @@ int8_t Plane::setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||
if (('y' != c) && ('Y' != c))
|
||||
return(-1);
|
||||
AP_Param::erase_all();
|
||||
cliSerial->printf_P(PSTR("\nFACTORY RESET complete - please reset board to continue"));
|
||||
cliSerial->printf_P("\nFACTORY RESET complete - please reset board to continue");
|
||||
|
||||
for (;; ) {
|
||||
}
|
||||
|
@ -59,7 +59,7 @@ int8_t Plane::setup_erase(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
int c;
|
||||
|
||||
cliSerial->printf_P(PSTR("\nType 'Y' and hit Enter to erase all waypoint and parameter data, any other key to abort: "));
|
||||
cliSerial->printf_P("\nType 'Y' and hit Enter to erase all waypoint and parameter data, any other key to abort: ");
|
||||
|
||||
do {
|
||||
c = cliSerial->read();
|
||||
|
@ -73,9 +73,9 @@ int8_t Plane::setup_erase(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Plane::zero_eeprom(void)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
|
||||
cliSerial->printf_P("\nErasing EEPROM\n");
|
||||
StorageManager::erase();
|
||||
cliSerial->printf_P(PSTR("done\n"));
|
||||
cliSerial->printf_P("done\n");
|
||||
}
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
|
|
@ -12,16 +12,14 @@
|
|||
#if CLI_ENABLED == ENABLED
|
||||
|
||||
// This is the help function
|
||||
// PSTR is an AVR macro to read strings from flash memory
|
||||
// printf_P is a version of print_f that reads from flash memory
|
||||
int8_t Plane::main_menu_help(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Commands:\n"
|
||||
cliSerial->printf_P("Commands:\n"
|
||||
" logs log readback/setup mode\n"
|
||||
" setup setup mode\n"
|
||||
" test test mode\n"
|
||||
" reboot reboot to flight mode\n"
|
||||
"\n"));
|
||||
"\n");
|
||||
return(0);
|
||||
}
|
||||
|
||||
|
@ -85,8 +83,8 @@ void Plane::init_ardupilot()
|
|||
// initialise serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n"),
|
||||
cliSerial->printf_P("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n",
|
||||
hal.util->available_memory());
|
||||
|
||||
|
||||
|
@ -185,7 +183,7 @@ void Plane::init_ardupilot()
|
|||
compass_ok = true;
|
||||
#endif
|
||||
if (!compass_ok) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
cliSerial->println_P("Compass initialisation failed!");
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
|
@ -230,7 +228,7 @@ void Plane::init_ardupilot()
|
|||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
if (g.cli_enabled == 1) {
|
||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
|
||||
cliSerial->println_P(msg);
|
||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||
gcs[1].get_uart()->println_P(msg);
|
||||
|
@ -268,10 +266,10 @@ void Plane::startup_ground(void)
|
|||
{
|
||||
set_mode(INITIALISING);
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("<startup_ground> GROUND START"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
|
||||
|
||||
#if (GROUND_START_DELAY > 0)
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("<startup_ground> With Delay"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
|
||||
delay(GROUND_START_DELAY * 1000);
|
||||
#endif
|
||||
|
||||
|
@ -318,7 +316,7 @@ void Plane::startup_ground(void)
|
|||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
ins.set_dataflash(&DataFlash);
|
||||
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("\n\n Ready to FLY."));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"\n\n Ready to FLY.");
|
||||
}
|
||||
|
||||
enum FlightMode Plane::get_previous_mode() {
|
||||
|
@ -562,14 +560,14 @@ void Plane::startup_INS_ground(void)
|
|||
while (barometer.get_last_update() == 0) {
|
||||
// the barometer begins updating when we get the first
|
||||
// HIL_STATE message
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Waiting for first HIL_STATE message"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, PSTR("Beginning INS calibration; do not move plane"));
|
||||
gcs_send_text_P(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move plane");
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
|
||||
|
@ -590,7 +588,7 @@ void Plane::startup_INS_ground(void)
|
|||
// --------------------------
|
||||
zero_airspeed(true);
|
||||
} else {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("NO airspeed"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING,"NO airspeed");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -638,46 +636,46 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
{
|
||||
switch (mode) {
|
||||
case MANUAL:
|
||||
port->print_P(PSTR("Manual"));
|
||||
port->print_P("Manual");
|
||||
break;
|
||||
case CIRCLE:
|
||||
port->print_P(PSTR("Circle"));
|
||||
port->print_P("Circle");
|
||||
break;
|
||||
case STABILIZE:
|
||||
port->print_P(PSTR("Stabilize"));
|
||||
port->print_P("Stabilize");
|
||||
break;
|
||||
case TRAINING:
|
||||
port->print_P(PSTR("Training"));
|
||||
port->print_P("Training");
|
||||
break;
|
||||
case ACRO:
|
||||
port->print_P(PSTR("ACRO"));
|
||||
port->print_P("ACRO");
|
||||
break;
|
||||
case FLY_BY_WIRE_A:
|
||||
port->print_P(PSTR("FBW_A"));
|
||||
port->print_P("FBW_A");
|
||||
break;
|
||||
case AUTOTUNE:
|
||||
port->print_P(PSTR("AUTOTUNE"));
|
||||
port->print_P("AUTOTUNE");
|
||||
break;
|
||||
case FLY_BY_WIRE_B:
|
||||
port->print_P(PSTR("FBW_B"));
|
||||
port->print_P("FBW_B");
|
||||
break;
|
||||
case CRUISE:
|
||||
port->print_P(PSTR("CRUISE"));
|
||||
port->print_P("CRUISE");
|
||||
break;
|
||||
case AUTO:
|
||||
port->print_P(PSTR("AUTO"));
|
||||
port->print_P("AUTO");
|
||||
break;
|
||||
case RTL:
|
||||
port->print_P(PSTR("RTL"));
|
||||
port->print_P("RTL");
|
||||
break;
|
||||
case LOITER:
|
||||
port->print_P(PSTR("Loiter"));
|
||||
port->print_P("Loiter");
|
||||
break;
|
||||
case GUIDED:
|
||||
port->print_P(PSTR("Guided"));
|
||||
port->print_P("Guided");
|
||||
break;
|
||||
default:
|
||||
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
||||
port->printf_P("Mode(%u)", (unsigned)mode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -685,7 +683,7 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
#if CLI_ENABLED == ENABLED
|
||||
void Plane::print_comma(void)
|
||||
{
|
||||
cliSerial->print_P(PSTR(","));
|
||||
cliSerial->print_P(",");
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@ bool Plane::auto_takeoff_check(void)
|
|||
|
||||
// Reset states if process has been interrupted
|
||||
if (last_check_ms && (now - last_check_ms) > 200) {
|
||||
gcs_send_text_fmt(PSTR("Timer Interrupted AUTO"));
|
||||
gcs_send_text_fmt("Timer Interrupted AUTO");
|
||||
launchTimerStarted = false;
|
||||
last_tkoff_arm_time = 0;
|
||||
last_check_ms = now;
|
||||
|
@ -48,13 +48,13 @@ bool Plane::auto_takeoff_check(void)
|
|||
if (!launchTimerStarted) {
|
||||
launchTimerStarted = true;
|
||||
last_tkoff_arm_time = now;
|
||||
gcs_send_text_fmt(PSTR("Armed AUTO, xaccel = %.1f m/s/s, waiting %.1f sec"),
|
||||
gcs_send_text_fmt("Armed AUTO, xaccel = %.1f m/s/s, waiting %.1f sec",
|
||||
(double)SpdHgt_Controller->get_VXdot(), (double)(wait_time_ms*0.001f));
|
||||
}
|
||||
|
||||
// Only perform velocity check if not timed out
|
||||
if ((now - last_tkoff_arm_time) > wait_time_ms+100U) {
|
||||
gcs_send_text_fmt(PSTR("Timeout AUTO"));
|
||||
gcs_send_text_fmt("Timeout AUTO");
|
||||
goto no_launch;
|
||||
}
|
||||
|
||||
|
@ -62,14 +62,14 @@ bool Plane::auto_takeoff_check(void)
|
|||
if (ahrs.pitch_sensor <= -3000 ||
|
||||
ahrs.pitch_sensor >= 4500 ||
|
||||
labs(ahrs.roll_sensor) > 3000) {
|
||||
gcs_send_text_fmt(PSTR("Bad Launch AUTO"));
|
||||
gcs_send_text_fmt("Bad Launch AUTO");
|
||||
goto no_launch;
|
||||
}
|
||||
|
||||
// Check ground speed and time delay
|
||||
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || is_zero(g.takeoff_throttle_min_speed))) &&
|
||||
((now - last_tkoff_arm_time) >= wait_time_ms)) {
|
||||
gcs_send_text_fmt(PSTR("Triggered AUTO, GPSspd = %.1f"), (double)gps.ground_speed());
|
||||
gcs_send_text_fmt("Triggered AUTO, GPSspd = %.1f", (double)gps.ground_speed());
|
||||
launchTimerStarted = false;
|
||||
last_tkoff_arm_time = 0;
|
||||
return true;
|
||||
|
@ -179,7 +179,7 @@ int8_t Plane::takeoff_tail_hold(void)
|
|||
|
||||
return_zero:
|
||||
if (auto_state.fbwa_tdrag_takeoff_mode) {
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("FBWA tdrag off"));
|
||||
gcs_send_text_P(MAV_SEVERITY_WARNING, "FBWA tdrag off");
|
||||
auto_state.fbwa_tdrag_takeoff_mode = false;
|
||||
}
|
||||
return 0;
|
||||
|
|
|
@ -40,14 +40,14 @@ MENU(test_menu, "test", test_menu_commands);
|
|||
|
||||
int8_t Plane::test_mode(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Test Mode\n\n"));
|
||||
cliSerial->printf_P("Test Mode\n\n");
|
||||
test_menu.run();
|
||||
return 0;
|
||||
}
|
||||
|
||||
void Plane::print_hit_enter()
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
cliSerial->printf_P("Hit Enter to exit.\n\n");
|
||||
}
|
||||
|
||||
int8_t Plane::test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
||||
|
@ -62,7 +62,7 @@ int8_t Plane::test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
|||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
|
||||
cliSerial->printf_P(PSTR("IN:\t1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
cliSerial->printf_P("IN:\t1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n",
|
||||
(int)channel_roll->radio_in,
|
||||
(int)channel_pitch->radio_in,
|
||||
(int)channel_throttle->radio_in,
|
||||
|
@ -89,7 +89,7 @@ int8_t Plane::test_passthru(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
// New radio frame? (we could use also if((millis()- timer) > 20)
|
||||
if (hal.rcin->new_input()) {
|
||||
cliSerial->print_P(PSTR("CH:"));
|
||||
cliSerial->print_P("CH:");
|
||||
for(int16_t i = 0; i < 8; i++) {
|
||||
cliSerial->print(hal.rcin->read(i)); // Print channel values
|
||||
print_comma();
|
||||
|
@ -126,7 +126,7 @@ int8_t Plane::test_radio(uint8_t argc, const Menu::arg *argv)
|
|||
// ------------------------------
|
||||
set_servos();
|
||||
|
||||
cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
cliSerial->printf_P("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n",
|
||||
(int)channel_roll->control_in,
|
||||
(int)channel_pitch->control_in,
|
||||
(int)channel_throttle->control_in,
|
||||
|
@ -157,7 +157,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
oldSwitchPosition = readSwitch();
|
||||
|
||||
cliSerial->printf_P(PSTR("Unplug battery, throttle in neutral, turn off radio.\n"));
|
||||
cliSerial->printf_P("Unplug battery, throttle in neutral, turn off radio.\n");
|
||||
while(channel_throttle->control_in > 0) {
|
||||
hal.scheduler->delay(20);
|
||||
read_radio();
|
||||
|
@ -168,19 +168,19 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
read_radio();
|
||||
|
||||
if(channel_throttle->control_in > 0) {
|
||||
cliSerial->printf_P(PSTR("THROTTLE CHANGED %d \n"), (int)channel_throttle->control_in);
|
||||
cliSerial->printf_P("THROTTLE CHANGED %d \n", (int)channel_throttle->control_in);
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if(oldSwitchPosition != readSwitch()) {
|
||||
cliSerial->printf_P(PSTR("CONTROL MODE CHANGED: "));
|
||||
cliSerial->printf_P("CONTROL MODE CHANGED: ");
|
||||
print_flight_mode(cliSerial, readSwitch());
|
||||
cliSerial->println();
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if(rc_failsafe_active()) {
|
||||
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)channel_throttle->radio_in);
|
||||
cliSerial->printf_P("THROTTLE FAILSAFE ACTIVATED: %d, ", (int)channel_throttle->radio_in);
|
||||
print_flight_mode(cliSerial, readSwitch());
|
||||
cliSerial->println();
|
||||
fail_test++;
|
||||
|
@ -190,7 +190,7 @@ int8_t Plane::test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
return (0);
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
cliSerial->printf_P(PSTR("LOS caused no change in APM.\n"));
|
||||
cliSerial->printf_P("LOS caused no change in APM.\n");
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
@ -202,14 +202,14 @@ int8_t Plane::test_relay(uint8_t argc, const Menu::arg *argv)
|
|||
hal.scheduler->delay(1000);
|
||||
|
||||
while(1) {
|
||||
cliSerial->printf_P(PSTR("Relay on\n"));
|
||||
cliSerial->printf_P("Relay on\n");
|
||||
relay.on(0);
|
||||
hal.scheduler->delay(3000);
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("Relay off\n"));
|
||||
cliSerial->printf_P("Relay off\n");
|
||||
relay.off(0);
|
||||
hal.scheduler->delay(3000);
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -224,14 +224,14 @@ int8_t Plane::test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
// save the alitude above home option
|
||||
if (g.RTL_altitude_cm < 0) {
|
||||
cliSerial->printf_P(PSTR("Hold current altitude\n"));
|
||||
cliSerial->printf_P("Hold current altitude\n");
|
||||
}else{
|
||||
cliSerial->printf_P(PSTR("Hold altitude of %dm\n"), (int)g.RTL_altitude_cm/100);
|
||||
cliSerial->printf_P("Hold altitude of %dm\n", (int)g.RTL_altitude_cm/100);
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("%d waypoints\n"), (int)mission.num_commands());
|
||||
cliSerial->printf_P(PSTR("Hit radius: %d\n"), (int)g.waypoint_radius);
|
||||
cliSerial->printf_P(PSTR("Loiter radius: %d\n\n"), (int)g.loiter_radius);
|
||||
cliSerial->printf_P("%d waypoints\n", (int)mission.num_commands());
|
||||
cliSerial->printf_P("Hit radius: %d\n", (int)g.waypoint_radius);
|
||||
cliSerial->printf_P("Loiter radius: %d\n\n", (int)g.loiter_radius);
|
||||
|
||||
for(uint8_t i = 0; i <= mission.num_commands(); i++) {
|
||||
AP_Mission::Mission_Command temp_cmd;
|
||||
|
@ -245,7 +245,7 @@ int8_t Plane::test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
void Plane::test_wp_print(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n"),
|
||||
cliSerial->printf_P("command #: %d id:%d options:%d p1:%d p2:%ld p3:%ld p4:%ld \n",
|
||||
(int)cmd.index,
|
||||
(int)cmd.id,
|
||||
(int)cmd.content.location.options,
|
||||
|
@ -259,7 +259,7 @@ int8_t Plane::test_xbee(uint8_t argc, const Menu::arg *argv)
|
|||
{
|
||||
print_hit_enter();
|
||||
hal.scheduler->delay(1000);
|
||||
cliSerial->printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n"));
|
||||
cliSerial->printf_P("Begin XBee X-CTU Range and RSSI Test:\n");
|
||||
|
||||
while(1) {
|
||||
|
||||
|
@ -278,7 +278,7 @@ int8_t Plane::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||
print_hit_enter();
|
||||
hal.scheduler->delay(1000);
|
||||
|
||||
cliSerial->printf_P(PSTR("Control CH "));
|
||||
cliSerial->printf_P("Control CH ");
|
||||
|
||||
cliSerial->println(FLIGHT_MODE_CHANNEL, BASE_DEC);
|
||||
|
||||
|
@ -286,7 +286,7 @@ int8_t Plane::test_modeswitch(uint8_t argc, const Menu::arg *argv)
|
|||
hal.scheduler->delay(20);
|
||||
uint8_t switchPosition = readSwitch();
|
||||
if (oldSwitchPosition != switchPosition) {
|
||||
cliSerial->printf_P(PSTR("Position %d\n"), (int)switchPosition);
|
||||
cliSerial->printf_P("Position %d\n", (int)switchPosition);
|
||||
oldSwitchPosition = switchPosition;
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -324,11 +324,11 @@ int8_t Plane::test_adc(uint8_t argc, const Menu::arg *argv)
|
|||
print_hit_enter();
|
||||
apm1_adc.Init();
|
||||
hal.scheduler->delay(1000);
|
||||
cliSerial->printf_P(PSTR("ADC\n"));
|
||||
cliSerial->printf_P("ADC\n");
|
||||
hal.scheduler->delay(1000);
|
||||
|
||||
while(1) {
|
||||
for (int8_t i=0; i<9; i++) cliSerial->printf_P(PSTR("%.1f\t"),apm1_adc.Ch(i));
|
||||
for (int8_t i=0; i<9; i++) cliSerial->printf_P("%.1f\t",apm1_adc.Ch(i));
|
||||
cliSerial->println();
|
||||
hal.scheduler->delay(100);
|
||||
if(cliSerial->available() > 0) {
|
||||
|
@ -352,13 +352,13 @@ int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
|
|||
if (gps.last_message_time_ms() != last_message_time_ms) {
|
||||
last_message_time_ms = gps.last_message_time_ms();
|
||||
const Location &loc = gps.location();
|
||||
cliSerial->printf_P(PSTR("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n"),
|
||||
cliSerial->printf_P("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n",
|
||||
(long)loc.lat,
|
||||
(long)loc.lng,
|
||||
(long)loc.alt/100,
|
||||
(int)gps.num_sats());
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("."));
|
||||
cliSerial->printf_P(".");
|
||||
}
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
|
@ -368,7 +368,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)
|
||||
{
|
||||
//cliSerial->printf_P(PSTR("Calibrating."));
|
||||
//cliSerial->printf_P("Calibrating.");
|
||||
ahrs.init();
|
||||
ahrs.set_fly_forward(true);
|
||||
ahrs.set_wind_estimation(true);
|
||||
|
@ -402,7 +402,7 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
// ---------------------
|
||||
Vector3f gyros = ins.get_gyro();
|
||||
Vector3f accels = ins.get_accel();
|
||||
cliSerial->printf_P(PSTR("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n"),
|
||||
cliSerial->printf_P("r:%4d p:%4d y:%3d g=(%5.1f %5.1f %5.1f) a=(%5.1f %5.1f %5.1f)\n",
|
||||
(int)ahrs.roll_sensor / 100,
|
||||
(int)ahrs.pitch_sensor / 100,
|
||||
(uint16_t)ahrs.yaw_sensor / 100,
|
||||
|
@ -419,13 +419,13 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
|
|||
int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
if (!g.compass_enabled) {
|
||||
cliSerial->printf_P(PSTR("Compass: "));
|
||||
cliSerial->printf_P("Compass: ");
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}
|
||||
|
||||
if (!compass.init()) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
cliSerial->println_P("Compass initialisation failed!");
|
||||
return 0;
|
||||
}
|
||||
ahrs.init();
|
||||
|
@ -465,12 +465,12 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
if (compass.healthy()) {
|
||||
const Vector3f &mag_ofs = compass.get_offsets();
|
||||
const Vector3f &mag = compass.get_field();
|
||||
cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),
|
||||
cliSerial->printf_P("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n",
|
||||
(wrap_360_cd(ToDeg(heading) * 100)) /100,
|
||||
(double)mag.x, (double)mag.y, (double)mag.z,
|
||||
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
|
||||
} else {
|
||||
cliSerial->println_P(PSTR("compass not healthy"));
|
||||
cliSerial->println_P("compass not healthy");
|
||||
}
|
||||
counter=0;
|
||||
}
|
||||
|
@ -482,7 +482,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
// save offsets. This allows you to get sane offset values using
|
||||
// the CLI before you go flying.
|
||||
cliSerial->println_P(PSTR("saving offsets"));
|
||||
cliSerial->println_P("saving offsets");
|
||||
compass.save_offsets();
|
||||
return (0);
|
||||
}
|
||||
|
@ -493,19 +493,19 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
int8_t Plane::test_airspeed(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
if (!airspeed.enabled()) {
|
||||
cliSerial->printf_P(PSTR("airspeed: "));
|
||||
cliSerial->printf_P("airspeed: ");
|
||||
print_enabled(false);
|
||||
return (0);
|
||||
}else{
|
||||
print_hit_enter();
|
||||
zero_airspeed(false);
|
||||
cliSerial->printf_P(PSTR("airspeed: "));
|
||||
cliSerial->printf_P("airspeed: ");
|
||||
print_enabled(true);
|
||||
|
||||
while(1) {
|
||||
hal.scheduler->delay(20);
|
||||
read_airspeed();
|
||||
cliSerial->printf_P(PSTR("%.1f m/s\n"), (double)airspeed.get_airspeed());
|
||||
cliSerial->printf_P("%.1f m/s\n", (double)airspeed.get_airspeed());
|
||||
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
|
@ -517,7 +517,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)
|
||||
{
|
||||
cliSerial->printf_P(PSTR("Uncalibrated relative airpressure\n"));
|
||||
cliSerial->printf_P("Uncalibrated relative airpressure\n");
|
||||
print_hit_enter();
|
||||
|
||||
init_barometer();
|
||||
|
@ -527,9 +527,9 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
|
|||
barometer.update();
|
||||
|
||||
if (!barometer.healthy()) {
|
||||
cliSerial->println_P(PSTR("not healthy"));
|
||||
cliSerial->println_P("not healthy");
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||
cliSerial->printf_P("Alt: %0.2fm, Raw: %f Temperature: %.1f\n",
|
||||
(double)barometer.get_altitude(),
|
||||
(double)barometer.get_pressure(),
|
||||
(double)barometer.get_temperature());
|
||||
|
@ -544,11 +544,11 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
|
|||
void Plane::print_enabled(bool b)
|
||||
{
|
||||
if (b) {
|
||||
cliSerial->printf_P(PSTR("en"));
|
||||
cliSerial->printf_P("en");
|
||||
} else {
|
||||
cliSerial->printf_P(PSTR("dis"));
|
||||
cliSerial->printf_P("dis");
|
||||
}
|
||||
cliSerial->printf_P(PSTR("abled\n"));
|
||||
cliSerial->printf_P("abled\n");
|
||||
}
|
||||
|
||||
#endif // CLI_ENABLED
|
||||
|
|
|
@ -11,7 +11,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
|
||||
void setup()
|
||||
{
|
||||
hal.console->println_P(PSTR("hello world"));
|
||||
hal.console->println_P("hello world");
|
||||
}
|
||||
|
||||
void loop()
|
||||
|
|
|
@ -90,7 +90,7 @@ public:
|
|||
AP_InertialNav_NavEKF inertial_nav{ahrs};
|
||||
AP_Vehicle::FixedWing aparm;
|
||||
AP_Airspeed airspeed{aparm};
|
||||
DataFlash_Class dataflash{PSTR("Replay v0.1")};
|
||||
DataFlash_Class dataflash{"Replay v0.1"};
|
||||
|
||||
private:
|
||||
Parameters g;
|
||||
|
@ -147,7 +147,7 @@ const AP_Param::Info ReplayVehicle::var_info[] PROGMEM = {
|
|||
void ReplayVehicle::load_parameters(void)
|
||||
{
|
||||
if (!AP_Param::check_var_info()) {
|
||||
hal.scheduler->panic(PSTR("Bad parameter table"));
|
||||
hal.scheduler->panic("Bad parameter table");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -274,10 +274,10 @@ void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix)
|
|||
}
|
||||
char key[AP_MAX_NAME_SIZE+1];
|
||||
if (type == AUTOTUNE_ROLL) {
|
||||
strncpy_P(key, PSTR("RLL2SRV_"), 8);
|
||||
strncpy_P(key, "RLL2SRV_", 8);
|
||||
strncpy_P(&key[8], suffix, AP_MAX_NAME_SIZE-8);
|
||||
} else {
|
||||
strncpy_P(key, PSTR("PTCH2SRV_"), 9);
|
||||
strncpy_P(key, "PTCH2SRV_", 9);
|
||||
strncpy_P(&key[9], suffix, AP_MAX_NAME_SIZE-9);
|
||||
}
|
||||
key[AP_MAX_NAME_SIZE] = 0;
|
||||
|
@ -318,12 +318,12 @@ void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const prog_c
|
|||
void AP_AutoTune::save_gains(const ATGains &v)
|
||||
{
|
||||
current = last_save;
|
||||
save_float_if_changed(current.tau, v.tau, PSTR("TCONST"));
|
||||
save_float_if_changed(current.P, v.P, PSTR("P"));
|
||||
save_float_if_changed(current.I, v.I, PSTR("I"));
|
||||
save_float_if_changed(current.D, v.D, PSTR("D"));
|
||||
save_int16_if_changed(current.rmax, v.rmax, PSTR("RMAX"));
|
||||
save_int16_if_changed(current.imax, v.imax, PSTR("IMAX"));
|
||||
save_float_if_changed(current.tau, v.tau, "TCONST");
|
||||
save_float_if_changed(current.P, v.P, "P");
|
||||
save_float_if_changed(current.I, v.I, "I");
|
||||
save_float_if_changed(current.D, v.D, "D");
|
||||
save_int16_if_changed(current.rmax, v.rmax, "RMAX");
|
||||
save_int16_if_changed(current.imax, v.imax, "IMAX");
|
||||
last_save = current;
|
||||
}
|
||||
|
||||
|
|
|
@ -131,7 +131,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
// we always check for fence breach
|
||||
if (geofence_breached || check_altlimit()) {
|
||||
if (!_terminate) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Fence TERMINATE"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Fence TERMINATE");
|
||||
_terminate.set(1);
|
||||
}
|
||||
}
|
||||
|
@ -142,7 +142,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
_rc_fail_time != 0 &&
|
||||
(hal.scheduler->millis() - last_valid_rc_ms) > (unsigned)_rc_fail_time.get()) {
|
||||
if (!_terminate) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("RC failure terminate"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "RC failure terminate");
|
||||
_terminate.set(1);
|
||||
}
|
||||
}
|
||||
|
@ -164,7 +164,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
// we startup in preflight mode. This mode ends when
|
||||
// we first enter auto.
|
||||
if (mode == OBC_AUTO) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Starting AFS_AUTO"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Starting AFS_AUTO");
|
||||
_state = STATE_AUTO;
|
||||
}
|
||||
break;
|
||||
|
@ -172,7 +172,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
case STATE_AUTO:
|
||||
// this is the normal mode.
|
||||
if (!gcs_link_ok) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("State DATA_LINK_LOSS"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "State DATA_LINK_LOSS");
|
||||
_state = STATE_DATA_LINK_LOSS;
|
||||
if (_wp_comms_hold) {
|
||||
_saved_wp = mission.get_current_nav_cmd().index;
|
||||
|
@ -186,7 +186,7 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
break;
|
||||
}
|
||||
if (!gps_lock_ok) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("State GPS_LOSS"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "State GPS_LOSS");
|
||||
_state = STATE_GPS_LOSS;
|
||||
if (_wp_gps_loss) {
|
||||
_saved_wp = mission.get_current_nav_cmd().index;
|
||||
|
@ -206,12 +206,12 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
// losing GPS lock when data link is lost
|
||||
// leads to termination
|
||||
if (!_terminate) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Dual loss TERMINATE"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Dual loss TERMINATE");
|
||||
_terminate.set(1);
|
||||
}
|
||||
} else if (gcs_link_ok) {
|
||||
_state = STATE_AUTO;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("GCS OK"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "GCS OK");
|
||||
// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
|
||||
if (_saved_wp != 0 &&
|
||||
(_max_comms_loss <= 0 ||
|
||||
|
@ -227,11 +227,11 @@ APM_OBC::check(APM_OBC::control_mode mode, uint32_t last_heartbeat_ms, bool geof
|
|||
// losing GCS link when GPS lock lost
|
||||
// leads to termination
|
||||
if (!_terminate) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Dual loss TERMINATE"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Dual loss TERMINATE");
|
||||
_terminate.set(1);
|
||||
}
|
||||
} else if (gps_lock_ok) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("GPS OK"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "GPS OK");
|
||||
_state = STATE_AUTO;
|
||||
// we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS
|
||||
if (_saved_wp != 0 &&
|
||||
|
|
|
@ -188,7 +188,7 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
|
|||
default:
|
||||
pga = 0.0f;
|
||||
hal.console->printf("Wrong gain");
|
||||
hal.scheduler->panic(PSTR("ADS1115: wrong gain selected"));
|
||||
hal.scheduler->panic("ADS1115: wrong gain selected");
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
|
@ -91,8 +91,8 @@ void AP_ADC_ADS7844::read(void)
|
|||
if (!got) {
|
||||
semfail_ctr++;
|
||||
if (semfail_ctr > 100) {
|
||||
hal.scheduler->panic(PSTR("PANIC: failed to take _spi_sem "
|
||||
"100 times in AP_ADC_ADS7844::read"));
|
||||
hal.scheduler->panic("PANIC: failed to take _spi_sem "
|
||||
"100 times in AP_ADC_ADS7844::read");
|
||||
}
|
||||
return;
|
||||
} else {
|
||||
|
@ -138,20 +138,20 @@ void AP_ADC_ADS7844::Init()
|
|||
hal.scheduler->suspend_timer_procs();
|
||||
_spi = hal.spi->device(AP_HAL::SPIDevice_ADS7844);
|
||||
if (_spi == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: AP_ADC_ADS7844 missing SPI device "
|
||||
"driver\n"));
|
||||
hal.scheduler->panic("PANIC: AP_ADC_ADS7844 missing SPI device "
|
||||
"driver\n");
|
||||
}
|
||||
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
|
||||
if (_spi_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: AP_ADC_ADS7844 missing SPI device "
|
||||
"semaphore"));
|
||||
hal.scheduler->panic("PANIC: AP_ADC_ADS7844 missing SPI device "
|
||||
"semaphore");
|
||||
}
|
||||
|
||||
if (!_spi_sem->take(0)) {
|
||||
hal.scheduler->panic(PSTR("PANIC: failed to take _spi_sem in"
|
||||
"AP_ADC_ADS7844::Init"));
|
||||
hal.scheduler->panic("PANIC: failed to take _spi_sem in"
|
||||
"AP_ADC_ADS7844::Init");
|
||||
}
|
||||
|
||||
_spi->cs_assert();
|
||||
|
|
|
@ -83,8 +83,8 @@ void loop(void)
|
|||
if (now - last_print >= 100000 /* 100ms : 10hz */) {
|
||||
Vector3f drift = ahrs.get_gyro_drift();
|
||||
hal.console->printf_P(
|
||||
PSTR("r:%4.1f p:%4.1f y:%4.1f "
|
||||
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n"),
|
||||
"r:%4.1f p:%4.1f y:%4.1f "
|
||||
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n",
|
||||
ToDeg(ahrs.roll),
|
||||
ToDeg(ahrs.pitch),
|
||||
ToDeg(ahrs.yaw),
|
||||
|
|
|
@ -195,7 +195,7 @@ void AP_Airspeed::calibrate(bool in_startup)
|
|||
}
|
||||
if (count == 0) {
|
||||
// unhealthy sensor
|
||||
hal.console->println_P(PSTR("Airspeed sensor unhealthy"));
|
||||
hal.console->println_P("Airspeed sensor unhealthy");
|
||||
_offset.set(0);
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -83,7 +83,7 @@ bool AP_Arming::barometer_checks(bool report)
|
|||
(checks_to_perform & ARMING_CHECK_BARO)) {
|
||||
if (!barometer.all_healthy()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Barometer not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Barometer not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -103,7 +103,7 @@ bool AP_Arming::airspeed_checks(bool report)
|
|||
}
|
||||
if (airspeed->enabled() && airspeed->use() && !airspeed->healthy()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: airspeed not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: airspeed not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -118,7 +118,7 @@ bool AP_Arming::logging_checks(bool report)
|
|||
(checks_to_perform & ARMING_CHECK_LOGGING)) {
|
||||
if (!logging_available) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: logging not available"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: logging not available");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -133,25 +133,25 @@ bool AP_Arming::ins_checks(bool report)
|
|||
const AP_InertialSensor &ins = ahrs.get_ins();
|
||||
if (!ins.get_gyro_health_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: gyros not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: gyros not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!ins.gyro_calibrated_ok_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: gyros not calibrated"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: gyros not calibrated");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!ins.get_accel_health_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: accels not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: accels not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!ins.accel_calibrated_ok_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: 3D accel cal needed"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: 3D accel cal needed");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -179,7 +179,7 @@ bool AP_Arming::ins_checks(bool report)
|
|||
}
|
||||
if (hal.scheduler->millis() - last_accel_pass_ms[i] > 10000) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: inconsistent Accelerometers"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: inconsistent Accelerometers");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -200,7 +200,7 @@ bool AP_Arming::ins_checks(bool report)
|
|||
}
|
||||
if (hal.scheduler->millis() - last_gyro_pass_ms[i] > 10000) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: inconsistent gyros"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: inconsistent gyros");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -223,14 +223,14 @@ bool AP_Arming::compass_checks(bool report)
|
|||
|
||||
if (!_compass.healthy()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass not healthy"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Compass not healthy");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
// check compass learning is on or offsets have been set
|
||||
if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass not calibrated"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Compass not calibrated");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -238,7 +238,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||
//check if compass is calibrating
|
||||
if (_compass.is_calibrating()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Arm: Compass calibration running"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Arm: Compass calibration running");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -246,7 +246,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||
//check if compass has calibrated and requires reboot
|
||||
if (_compass.compass_cal_requires_reboot()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass calibrated requires reboot"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibrated requires reboot");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -255,7 +255,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||
Vector3f offsets = _compass.get_offsets();
|
||||
if (offsets.length() > AP_ARMING_COMPASS_OFFSETS_MAX) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass offsets too high"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Compass offsets too high");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -264,7 +264,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||
float mag_field = _compass.get_field().length();
|
||||
if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Check mag field"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Check mag field");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -272,7 +272,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||
// check all compasses point in roughly same direction
|
||||
if (!_compass.consistent()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent compasses"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -291,7 +291,7 @@ bool AP_Arming::gps_checks(bool report)
|
|||
if (home_is_set == HOME_UNSET ||
|
||||
gps.status() < AP_GPS::GPS_OK_FIX_3D) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Bad GPS Position"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Bad GPS Position");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -307,7 +307,7 @@ bool AP_Arming::battery_checks(bool report)
|
|||
|
||||
if (AP_Notify::flags.failsafe_battery) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Battery failsafe on"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Battery failsafe on");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -321,7 +321,7 @@ bool AP_Arming::hardware_safety_check(bool report)
|
|||
// check if safety switch has been pushed
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Hardware Safety Switch"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Hardware Safety Switch");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -336,7 +336,7 @@ bool AP_Arming::manual_transmitter_checks(bool report)
|
|||
|
||||
if (AP_Notify::flags.failsafe_radio) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Radio failsafe on"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Radio failsafe on");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -356,7 +356,7 @@ bool AP_Arming::board_voltage_checks(bool report)
|
|||
if(!is_zero(hal.analogin->board_voltage()) &&
|
||||
((hal.analogin->board_voltage() < AP_ARMING_BOARD_VOLTAGE_MIN) || (hal.analogin->board_voltage() > AP_ARMING_BOARD_VOLTAGE_MAX))) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check Board Voltage"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -398,7 +398,7 @@ bool AP_Arming::arm(uint8_t method)
|
|||
if (checks_to_perform == ARMING_CHECK_NONE) {
|
||||
armed = true;
|
||||
arming_method = NONE;
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Throttle armed!"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle armed!");
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -406,7 +406,7 @@ bool AP_Arming::arm(uint8_t method)
|
|||
armed = true;
|
||||
arming_method = method;
|
||||
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Throttle armed!"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle armed!");
|
||||
|
||||
//TODO: Log motor arming to the dataflash
|
||||
//Can't do this from this class until there is a unified logging library
|
||||
|
@ -427,7 +427,7 @@ bool AP_Arming::disarm()
|
|||
}
|
||||
armed = false;
|
||||
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Throttle disarmed!"));
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle disarmed!");
|
||||
|
||||
//TODO: Log motor disarming to the dataflash
|
||||
//Can't do this from this class until there is a unified logging library.
|
||||
|
|
|
@ -104,8 +104,8 @@ void AP_Baro::calibrate()
|
|||
do {
|
||||
update();
|
||||
if (hal.scheduler->millis() - tstart > 500) {
|
||||
hal.scheduler->panic(PSTR("PANIC: AP_Baro::read unsuccessful "
|
||||
"for more than 500ms in AP_Baro::calibrate [2]\r\n"));
|
||||
hal.scheduler->panic("PANIC: AP_Baro::read unsuccessful "
|
||||
"for more than 500ms in AP_Baro::calibrate [2]\r\n");
|
||||
}
|
||||
hal.scheduler->delay(10);
|
||||
} while (!healthy());
|
||||
|
@ -124,8 +124,8 @@ void AP_Baro::calibrate()
|
|||
do {
|
||||
update();
|
||||
if (hal.scheduler->millis() - tstart > 500) {
|
||||
hal.scheduler->panic(PSTR("PANIC: AP_Baro::read unsuccessful "
|
||||
"for more than 500ms in AP_Baro::calibrate [3]\r\n"));
|
||||
hal.scheduler->panic("PANIC: AP_Baro::read unsuccessful "
|
||||
"for more than 500ms in AP_Baro::calibrate [3]\r\n");
|
||||
}
|
||||
} while (!healthy());
|
||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||
|
@ -152,7 +152,7 @@ void AP_Baro::calibrate()
|
|||
return;
|
||||
}
|
||||
}
|
||||
hal.scheduler->panic(PSTR("AP_Baro: all sensors uncalibrated"));
|
||||
hal.scheduler->panic("AP_Baro: all sensors uncalibrated");
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -322,7 +322,7 @@ void AP_Baro::init(void)
|
|||
}
|
||||
#endif
|
||||
if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == NULL) {
|
||||
hal.scheduler->panic(PSTR("Baro: unable to initialise driver"));
|
||||
hal.scheduler->panic("Baro: unable to initialise driver");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -396,7 +396,7 @@ void AP_Baro::accumulate(void)
|
|||
uint8_t AP_Baro::register_sensor(void)
|
||||
{
|
||||
if (_num_sensors >= BARO_MAX_INSTANCES) {
|
||||
hal.scheduler->panic(PSTR("Too many barometers"));
|
||||
hal.scheduler->panic("Too many barometers");
|
||||
}
|
||||
return _num_sensors++;
|
||||
}
|
||||
|
|
|
@ -68,7 +68,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro) :
|
|||
|
||||
// take i2c bus sempahore
|
||||
if (!i2c_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
hal.scheduler->panic(PSTR("BMP085: unable to get semaphore"));
|
||||
hal.scheduler->panic("BMP085: unable to get semaphore");
|
||||
}
|
||||
|
||||
// End Of Conversion (PC7) input
|
||||
|
@ -76,7 +76,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro) :
|
|||
|
||||
// We read the calibration data registers
|
||||
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {
|
||||
hal.scheduler->panic(PSTR("BMP085: bad calibration registers"));
|
||||
hal.scheduler->panic("BMP085: bad calibration registers");
|
||||
}
|
||||
|
||||
ac1 = ((int16_t)buff[0] << 8) | buff[1];
|
||||
|
|
|
@ -51,11 +51,11 @@ void AP_SerialBus_SPI::init()
|
|||
{
|
||||
_spi = hal.spi->device(_device);
|
||||
if (_spi == NULL) {
|
||||
hal.scheduler->panic(PSTR("did not get valid SPI device driver!"));
|
||||
hal.scheduler->panic("did not get valid SPI device driver!");
|
||||
}
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
if (_spi_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("AP_SerialBus_SPI did not get valid SPI semaphroe!"));
|
||||
hal.scheduler->panic("AP_SerialBus_SPI did not get valid SPI semaphroe!");
|
||||
}
|
||||
_spi->set_bus_speed(_speed);
|
||||
}
|
||||
|
@ -111,7 +111,7 @@ void AP_SerialBus_I2C::init()
|
|||
{
|
||||
_i2c_sem = _i2c->get_semaphore();
|
||||
if (_i2c_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("AP_SerialBus_I2C did not get valid I2C semaphore!"));
|
||||
hal.scheduler->panic("AP_SerialBus_I2C did not get valid I2C semaphore!");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -174,7 +174,7 @@ AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_tim
|
|||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
if (!_serial->sem_take_blocking()){
|
||||
hal.scheduler->panic(PSTR("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init"));
|
||||
hal.scheduler->panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init");
|
||||
}
|
||||
|
||||
_serial->write(CMD_MS5611_RESET);
|
||||
|
@ -190,7 +190,7 @@ AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_SerialBus *serial, bool use_tim
|
|||
_C6 = _serial->read_16bits(CMD_MS5611_PROM_C6);
|
||||
|
||||
if (!_check_crc()) {
|
||||
hal.scheduler->panic(PSTR("Bad CRC on MS5611"));
|
||||
hal.scheduler->panic("Bad CRC on MS5611");
|
||||
}
|
||||
|
||||
// Send a command to read Temp first
|
||||
|
|
|
@ -17,14 +17,14 @@ void test_high_low_byte(void)
|
|||
for (i=0; i<=300; i++) {
|
||||
high = HIGHBYTE(i);
|
||||
low = LOWBYTE(i);
|
||||
hal.console->printf_P(PSTR("\ni:%u high:%u low:%u"),(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||
hal.console->printf_P("\ni:%u high:%u low:%u",(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||
}
|
||||
|
||||
// test values from 300 to 65400 at increments of 200
|
||||
for (i=301; i<=65400; i+=200) {
|
||||
high = HIGHBYTE(i);
|
||||
low = LOWBYTE(i);
|
||||
hal.console->printf_P(PSTR("\ni:%u high:%u low:%u"),(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||
hal.console->printf_P("\ni:%u high:%u low:%u",(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -276,17 +276,17 @@ AP_Compass_HMC5843::init()
|
|||
hal.scheduler->suspend_timer_procs();
|
||||
|
||||
if (!_bus_sem || !_bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
hal.console->printf_P(PSTR("HMC5843: Unable to get bus semaphore\n"));
|
||||
hal.console->printf_P("HMC5843: Unable to get bus semaphore\n");
|
||||
goto fail_sem;
|
||||
}
|
||||
|
||||
if (!_bus->configure()) {
|
||||
hal.console->printf_P(PSTR("HMC5843: Could not configure the bus\n"));
|
||||
hal.console->printf_P("HMC5843: Could not configure the bus\n");
|
||||
goto errout;
|
||||
}
|
||||
|
||||
if (!_detect_version()) {
|
||||
hal.console->printf_P(PSTR("HMC5843: Could not detect version\n"));
|
||||
hal.console->printf_P("HMC5843: Could not detect version\n");
|
||||
goto errout;
|
||||
}
|
||||
|
||||
|
@ -303,7 +303,7 @@ AP_Compass_HMC5843::init()
|
|||
}
|
||||
|
||||
if (!_calibrate(calibration_gain, expected_x, expected_yz)) {
|
||||
hal.console->printf_P(PSTR("HMC5843: Could not calibrate sensor\n"));
|
||||
hal.console->printf_P("HMC5843: Could not calibrate sensor\n");
|
||||
goto errout;
|
||||
}
|
||||
|
||||
|
@ -313,7 +313,7 @@ AP_Compass_HMC5843::init()
|
|||
}
|
||||
|
||||
if (!_bus->start_measurements()) {
|
||||
hal.console->printf_P(PSTR("HMC5843: Could not start measurements on bus\n"));
|
||||
hal.console->printf_P("HMC5843: Could not start measurements on bus\n");
|
||||
goto errout;
|
||||
}
|
||||
_initialised = true;
|
||||
|
@ -325,7 +325,7 @@ AP_Compass_HMC5843::init()
|
|||
read();
|
||||
|
||||
#if 0
|
||||
hal.console->printf_P(PSTR("CalX: %.2f CalY: %.2f CalZ: %.2f\n"),
|
||||
hal.console->printf_P("CalX: %.2f CalY: %.2f CalZ: %.2f\n",
|
||||
_scaling[0], _scaling[1], _scaling[2]);
|
||||
#endif
|
||||
|
||||
|
@ -376,13 +376,13 @@ bool AP_Compass_HMC5843::_calibrate(uint8_t calibration_gain,
|
|||
|
||||
float cal[3];
|
||||
|
||||
// hal.console->printf_P(PSTR("mag %d %d %d\n"), _mag_x, _mag_y, _mag_z);
|
||||
// hal.console->printf_P("mag %d %d %d\n", _mag_x, _mag_y, _mag_z);
|
||||
|
||||
cal[0] = fabsf(expected_x / (float)_mag_x);
|
||||
cal[1] = fabsf(expected_yz / (float)_mag_y);
|
||||
cal[2] = fabsf(expected_yz / (float)_mag_z);
|
||||
|
||||
// hal.console->printf_P(PSTR("cal=%.2f %.2f %.2f\n"), cal[0], cal[1], cal[2]);
|
||||
// hal.console->printf_P("cal=%.2f %.2f %.2f\n", cal[0], cal[1], cal[2]);
|
||||
|
||||
// we throw away the first two samples as the compass may
|
||||
// still be changing its state from the application of the
|
||||
|
@ -398,7 +398,7 @@ bool AP_Compass_HMC5843::_calibrate(uint8_t calibration_gain,
|
|||
if (IS_CALIBRATION_VALUE_VALID(cal[0]) &&
|
||||
IS_CALIBRATION_VALUE_VALID(cal[1]) &&
|
||||
IS_CALIBRATION_VALUE_VALID(cal[2])) {
|
||||
// hal.console->printf_P(PSTR("car=%.2f %.2f %.2f good\n"), cal[0], cal[1], cal[2]);
|
||||
// hal.console->printf_P("car=%.2f %.2f %.2f good\n", cal[0], cal[1], cal[2]);
|
||||
good_count++;
|
||||
|
||||
_scaling[0] += cal[0];
|
||||
|
@ -410,8 +410,8 @@ bool AP_Compass_HMC5843::_calibrate(uint8_t calibration_gain,
|
|||
|
||||
#if 0
|
||||
/* useful for debugging */
|
||||
hal.console->printf_P(PSTR("MagX: %d MagY: %d MagZ: %d\n"), (int)_mag_x, (int)_mag_y, (int)_mag_z);
|
||||
hal.console->printf_P(PSTR("CalX: %.2f CalY: %.2f CalZ: %.2f\n"), cal[0], cal[1], cal[2]);
|
||||
hal.console->printf_P("MagX: %d MagY: %d MagZ: %d\n", (int)_mag_x, (int)_mag_y, (int)_mag_z);
|
||||
hal.console->printf_P("CalX: %.2f CalY: %.2f CalZ: %.2f\n", cal[0], cal[1], cal[2]);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -240,7 +240,7 @@ bool AP_Compass_LSM303D::_read_raw()
|
|||
{
|
||||
if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) {
|
||||
hal.console->println_P(
|
||||
PSTR("LSM303D _read_data_transaction_accel: _reg7_expected unexpected"));
|
||||
"LSM303D _read_data_transaction_accel: _reg7_expected unexpected");
|
||||
// reset();
|
||||
return false;
|
||||
}
|
||||
|
@ -302,7 +302,7 @@ AP_Compass_LSM303D::init()
|
|||
uint8_t whoami = _register_read(ADDR_WHO_AM_I);
|
||||
if (whoami != WHO_I_AM) {
|
||||
hal.console->printf("LSM303D: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
|
||||
hal.scheduler->panic(PSTR("LSM303D: bad WHOAMI"));
|
||||
hal.scheduler->panic("LSM303D: bad WHOAMI");
|
||||
}
|
||||
|
||||
uint8_t tries = 0;
|
||||
|
@ -312,19 +312,19 @@ AP_Compass_LSM303D::init()
|
|||
if (success) {
|
||||
hal.scheduler->delay(5+2);
|
||||
if (!_spi_sem->take(100)) {
|
||||
hal.scheduler->panic(PSTR("LSM303D: Unable to get semaphore"));
|
||||
hal.scheduler->panic("LSM303D: Unable to get semaphore");
|
||||
}
|
||||
if (_data_ready()) {
|
||||
_spi_sem->give();
|
||||
break;
|
||||
} else {
|
||||
hal.console->println_P(
|
||||
PSTR("LSM303D startup failed: no data ready"));
|
||||
"LSM303D startup failed: no data ready");
|
||||
}
|
||||
_spi_sem->give();
|
||||
}
|
||||
if (tries++ > 5) {
|
||||
hal.scheduler->panic(PSTR("PANIC: failed to boot LSM303D 5 times"));
|
||||
hal.scheduler->panic("PANIC: failed to boot LSM303D 5 times");
|
||||
}
|
||||
} while (1);
|
||||
|
||||
|
@ -356,7 +356,7 @@ uint32_t AP_Compass_LSM303D::get_dev_id()
|
|||
bool AP_Compass_LSM303D::_hardware_init(void)
|
||||
{
|
||||
if (!_spi_sem->take(100)) {
|
||||
hal.scheduler->panic(PSTR("LSM303D: Unable to get semaphore"));
|
||||
hal.scheduler->panic("LSM303D: Unable to get semaphore");
|
||||
}
|
||||
|
||||
// initially run the bus at low speed
|
||||
|
|
|
@ -401,7 +401,7 @@ Compass::init()
|
|||
uint8_t Compass::register_compass(void)
|
||||
{
|
||||
if (_compass_count == COMPASS_MAX_INSTANCES) {
|
||||
hal.scheduler->panic(PSTR("Too many compass instances"));
|
||||
hal.scheduler->panic("Too many compass instances");
|
||||
}
|
||||
return _compass_count++;
|
||||
}
|
||||
|
@ -411,7 +411,7 @@ void Compass::_add_backend(AP_Compass_Backend *backend)
|
|||
if (!backend)
|
||||
return;
|
||||
if (_backend_count == COMPASS_MAX_BACKEND)
|
||||
hal.scheduler->panic(PSTR("Too many compass backends"));
|
||||
hal.scheduler->panic("Too many compass backends");
|
||||
_backends[_backend_count++] = backend;
|
||||
}
|
||||
|
||||
|
@ -451,7 +451,7 @@ void Compass::_detect_backends(void)
|
|||
|
||||
if (_backend_count == 0 ||
|
||||
_compass_count == 0) {
|
||||
hal.console->println_P(PSTR("No Compass backends available"));
|
||||
hal.console->println_P("No Compass backends available");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -83,13 +83,13 @@ T AP_Curve<T,SIZE>::get_y( T x )
|
|||
template <class T, uint8_t SIZE>
|
||||
void AP_Curve<T,SIZE>::dump_curve(AP_HAL::BetterStream* s)
|
||||
{
|
||||
s->println_P(PSTR("Curve:"));
|
||||
s->println_P("Curve:");
|
||||
for( uint8_t i = 0; i<_num_points; i++ ){
|
||||
s->print_P(PSTR("x:"));
|
||||
s->print_P("x:");
|
||||
s->print(_x[i]);
|
||||
s->print_P(PSTR("\ty:"));
|
||||
s->print_P("\ty:");
|
||||
s->print(_y[i]);
|
||||
s->print_P(PSTR("\tslope:"));
|
||||
s->print_P("\tslope:");
|
||||
s->print(_slope[i],4);
|
||||
s->println();
|
||||
}
|
||||
|
|
|
@ -200,7 +200,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
if (_type[instance] == GPS_TYPE_PX4) {
|
||||
// check for explicitely chosen PX4 GPS beforehand
|
||||
// it is not possible to autodetect it, nor does it require a real UART
|
||||
hal.console->print_P(PSTR(" PX4 "));
|
||||
hal.console->print_P(" PX4 ");
|
||||
new_gps = new AP_GPS_PX4(*this, state[instance], _port[instance]);
|
||||
goto found_gps;
|
||||
}
|
||||
|
@ -218,10 +218,10 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
#if GPS_RTK_AVAILABLE
|
||||
// by default the sbf/trimble gps outputs no data on its port, until configured.
|
||||
if (_type[instance] == GPS_TYPE_SBF) {
|
||||
hal.console->print_P(PSTR(" SBF "));
|
||||
hal.console->print_P(" SBF ");
|
||||
new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]);
|
||||
} else if ((_type[instance] == GPS_TYPE_GSOF)) {
|
||||
hal.console->print_P(PSTR(" GSOF "));
|
||||
hal.console->print_P(" GSOF ");
|
||||
new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#endif // GPS_RTK_AVAILABLE
|
||||
|
@ -265,23 +265,23 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) &&
|
||||
pgm_read_dword(&_baudrates[dstate->last_baud]) >= 38400 &&
|
||||
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" ublox "));
|
||||
hal.console->print_P(" ublox ");
|
||||
new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]);
|
||||
}
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
|
||||
AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" MTK19 "));
|
||||
hal.console->print_P(" MTK19 ");
|
||||
new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
|
||||
}
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
|
||||
AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" MTK "));
|
||||
hal.console->print_P(" MTK ");
|
||||
new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#if GPS_RTK_AVAILABLE
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
|
||||
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" SBP "));
|
||||
hal.console->print_P(" SBP ");
|
||||
new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
|
||||
}
|
||||
#endif // HAL_CPU_CLASS
|
||||
|
@ -289,7 +289,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
// save a bit of code space on a 1280
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
|
||||
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" SIRF "));
|
||||
hal.console->print_P(" SIRF ");
|
||||
new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
|
||||
}
|
||||
else if (now - dstate->detect_started_ms > (ARRAY_SIZE(_baudrates) * GPS_BAUD_TIME_MS)) {
|
||||
|
@ -297,7 +297,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||
// a MTK or UBLOX which has booted in NMEA mode
|
||||
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_NMEA) &&
|
||||
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" NMEA "));
|
||||
hal.console->print_P(" NMEA ");
|
||||
new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -79,7 +79,7 @@ AP_GPS_UBLOX::send_next_rate_update(void)
|
|||
return;
|
||||
}
|
||||
|
||||
//hal.console->printf_P(PSTR("next_rate: %u\n"), (unsigned)rate_update_step);
|
||||
//hal.console->printf_P("next_rate: %u\n", (unsigned)rate_update_step);
|
||||
|
||||
switch (rate_update_step++) {
|
||||
case 0:
|
||||
|
|
|
@ -5,7 +5,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
AP_HAL::AnalogSource* ch;
|
||||
|
||||
void setup (void) {
|
||||
hal.console->printf_P(PSTR("Starting AP_HAL::AnalogIn test\r\n"));
|
||||
hal.console->printf_P("Starting AP_HAL::AnalogIn test\r\n");
|
||||
ch = hal.analogin->channel(0);
|
||||
}
|
||||
|
||||
|
@ -17,7 +17,7 @@ void loop (void)
|
|||
if (pin == 0) {
|
||||
hal.console->println();
|
||||
}
|
||||
hal.console->printf_P(PSTR("[%u %.3f] "),
|
||||
hal.console->printf_P("[%u %.3f] ",
|
||||
(unsigned)pin, v);
|
||||
pin = (pin+1) % 16;
|
||||
ch->set_pin(pin);
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void setup(void) {
|
||||
hal.console->println_P(PSTR("Starting Printf test"));
|
||||
hal.console->println_P("Starting Printf test");
|
||||
}
|
||||
|
||||
static const struct {
|
||||
|
|
|
@ -13,7 +13,7 @@ void setup(void)
|
|||
/*
|
||||
init Storage API
|
||||
*/
|
||||
hal.console->printf_P(PSTR("Starting AP_HAL::Storage test\r\n"));
|
||||
hal.console->printf_P("Starting AP_HAL::Storage test\r\n");
|
||||
st->init(NULL);
|
||||
|
||||
/*
|
||||
|
@ -33,7 +33,7 @@ void setup(void)
|
|||
/*
|
||||
print XORed result
|
||||
*/
|
||||
hal.console->printf_P(PSTR("XORed ememory: %u\r\n"), (unsigned) XOR_res);
|
||||
hal.console->printf_P("XORed ememory: %u\r\n", (unsigned) XOR_res);
|
||||
}
|
||||
|
||||
// In main loop do nothing
|
||||
|
|
|
@ -223,9 +223,9 @@ void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt,
|
|||
}
|
||||
if (sign)
|
||||
s->write(sign);
|
||||
const prog_char_t *p = PSTR("inf");
|
||||
const prog_char_t *p = "inf";
|
||||
if (vtype & FTOA_NAN)
|
||||
p = PSTR("nan");
|
||||
p = "nan";
|
||||
while ( (ndigs = pgm_read_byte((const prog_char *)p)) != 0) {
|
||||
if (flags & FL_FLTUPP)
|
||||
ndigs += 'I' - 'i';
|
||||
|
|
|
@ -52,8 +52,8 @@ FLYMAPLEAnalogSource* FLYMAPLEAnalogIn::_create_channel(int16_t chnum) {
|
|||
void FLYMAPLEAnalogIn::_register_channel(FLYMAPLEAnalogSource* ch) {
|
||||
if (_num_channels >= FLYMAPLE_INPUT_MAX_CHANNELS) {
|
||||
for(;;) {
|
||||
hal.console->print_P(PSTR(
|
||||
"Error: AP_HAL_FLYMAPLE::FLYMAPLEAnalogIn out of channels\r\n"));
|
||||
hal.console->print_P(
|
||||
"Error: AP_HAL_FLYMAPLE::FLYMAPLEAnalogIn out of channels\r\n");
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -224,8 +224,8 @@ bool FLYMAPLEScheduler::system_initializing() {
|
|||
void FLYMAPLEScheduler::system_initialized()
|
||||
{
|
||||
if (_initialized) {
|
||||
panic(PSTR("PANIC: scheduler::system_initialized called"
|
||||
"more than once"));
|
||||
panic("PANIC: scheduler::system_initialized called"
|
||||
"more than once");
|
||||
}
|
||||
_initialized = true;
|
||||
}
|
||||
|
@ -247,7 +247,7 @@ void FLYMAPLEScheduler::panic(const prog_char_t *errormsg, ...) {
|
|||
}
|
||||
|
||||
void FLYMAPLEScheduler::reboot(bool hold_in_bootloader) {
|
||||
hal.uartA->println_P(PSTR("GOING DOWN FOR A REBOOT\r\n"));
|
||||
hal.uartA->println_P("GOING DOWN FOR A REBOOT\r\n");
|
||||
hal.scheduler->delay(100);
|
||||
nvic_sys_reset();
|
||||
}
|
||||
|
|
|
@ -44,8 +44,8 @@ bool FLYMAPLESemaphore::give() {
|
|||
|
||||
bool FLYMAPLESemaphore::take(uint32_t timeout_ms) {
|
||||
if (hal.scheduler->in_timerprocess()) {
|
||||
hal.scheduler->panic(PSTR("PANIC: FLYMAPLESemaphore::take used from "
|
||||
"inside timer process"));
|
||||
hal.scheduler->panic("PANIC: FLYMAPLESemaphore::take used from "
|
||||
"inside timer process");
|
||||
return false; /* Never reached - panic does not return */
|
||||
}
|
||||
return _take_from_mainloop(timeout_ms);
|
||||
|
|
|
@ -29,9 +29,9 @@ void setup(void)
|
|||
hal.console->println(1000, 8);
|
||||
hal.console->println(1000, 10);
|
||||
hal.console->println(1000, 16);
|
||||
hal.console->println_P(PSTR("progmem"));
|
||||
hal.console->printf("printf %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, PSTR("progmem"));
|
||||
hal.console->printf_P(PSTR("printf_P %d %u %#x %p %f %S\n"), -1000, 1000, 1000, 1000, 1.2345, PSTR("progmem"));
|
||||
hal.console->println_P("progmem");
|
||||
hal.console->printf("printf %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, "progmem");
|
||||
hal.console->printf_P("printf_P %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, "progmem");
|
||||
|
||||
hal.console->println("done.");
|
||||
for(;;);
|
||||
|
|
|
@ -17,14 +17,14 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
#define HMC5883L 0x1E
|
||||
|
||||
void setup() {
|
||||
hal.console->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"),
|
||||
hal.console->printf_P("Initializing HMC5883L at address %x\r\n",
|
||||
HMC5883L);
|
||||
|
||||
uint8_t stat = hal.i2c->writeRegister(HMC5883L,0x02,0x00);
|
||||
if (stat == 0) {
|
||||
hal.console->printf_P(PSTR("successful init\r\n"));
|
||||
hal.console->printf_P("successful init\r\n");
|
||||
} else {
|
||||
hal.console->printf_P(PSTR("failed init: return status %d\r\n"),
|
||||
hal.console->printf_P("failed init: return status %d\r\n",
|
||||
(int)stat);
|
||||
for(;;);
|
||||
}
|
||||
|
@ -43,9 +43,9 @@ void loop() {
|
|||
y |= data[3];
|
||||
z = data[4] << 8;
|
||||
z |= data[5];
|
||||
hal.console->printf_P(PSTR("x: %d y: %d z: %d \r\n"), x, y, z);
|
||||
hal.console->printf_P("x: %d y: %d z: %d \r\n", x, y, z);
|
||||
} else {
|
||||
hal.console->printf_P(PSTR("i2c error: status %d\r\n"), (int)stat);
|
||||
hal.console->printf_P("i2c error: status %d\r\n", (int)stat);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -15,7 +15,7 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
|||
valid = in->new_input();
|
||||
in->read(channels, 8);
|
||||
hal.console->printf_P(
|
||||
PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
"multi read %d: %d %d %d %d %d %d %d %d\r\n",
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
|
@ -29,7 +29,7 @@ void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
|
|||
channels[i] = in->read(i);
|
||||
}
|
||||
hal.console->printf_P(
|
||||
PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
"individual read %d: %d %d %d %d %d %d %d %d\r\n",
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
|
|
|
@ -14,7 +14,7 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
|||
uint8_t valid;
|
||||
valid = in->read(channels, 8);
|
||||
hal.console->printf_P(
|
||||
PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
"multi read %d: %d %d %d %d %d %d %d %d\r\n",
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
|
@ -28,7 +28,7 @@ void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
|
|||
channels[i] = in->read(i);
|
||||
}
|
||||
hal.console->printf_P(
|
||||
PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
"individual read %d: %d %d %d %d %d %d %d %d\r\n",
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
|
@ -76,7 +76,7 @@ void setup (void) {
|
|||
/* Bottom 4 channels at 400hz (like on a quad) */
|
||||
hal.rcout->set_freq(0x0000000F, 400);
|
||||
for(int i = 0; i < 12; i++) {
|
||||
hal.console->printf_P(PSTR("rcout ch %d has frequency %d\r\n"),
|
||||
hal.console->printf_P("rcout ch %d has frequency %d\r\n",
|
||||
i, hal.rcout->get_freq(i));
|
||||
}
|
||||
/* Delay to let the user see the above printouts on the terminal */
|
||||
|
|
|
@ -16,11 +16,11 @@ AP_HAL::SPIDeviceDriver* spidev;
|
|||
|
||||
void setup (void) {
|
||||
hal.scheduler->delay(5000);
|
||||
hal.console->printf_P(PSTR("Starting AP_HAL_FLYMAPLE::SPIDriver test\r\n"));
|
||||
hal.console->printf_P("Starting AP_HAL_FLYMAPLE::SPIDriver test\r\n");
|
||||
|
||||
spidev = hal.spi->device(AP_HAL::SPIDevice_MPU6000); // Not really MPU6000, just a generic SPU driver
|
||||
if (!spidev)
|
||||
hal.scheduler->panic(PSTR("Starting AP_HAL_FLYMAPLE::SPIDriver failed to get spidev\r\n"));
|
||||
hal.scheduler->panic("Starting AP_HAL_FLYMAPLE::SPIDriver failed to get spidev\r\n");
|
||||
}
|
||||
|
||||
void loop (void) {
|
||||
|
|
|
@ -53,7 +53,7 @@ void schedule_toggle_hang(void) {
|
|||
}
|
||||
|
||||
void setup_pin(int pin_num) {
|
||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||
hal.console->printf_P("Setup pin %d\r\n", pin_num);
|
||||
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||
/* Blink so we can see setup on the logic analyzer.*/
|
||||
hal.gpio->write(pin_num,1);
|
||||
|
@ -62,32 +62,32 @@ void setup_pin(int pin_num) {
|
|||
|
||||
void setup (void) {
|
||||
// hal.scheduler->delay(5000);
|
||||
hal.console->printf_P(PSTR("Starting AP_HAL_AVR::Scheduler test\r\n"));
|
||||
hal.console->printf_P("Starting AP_HAL_AVR::Scheduler test\r\n");
|
||||
|
||||
setup_pin(DELAY_TOGGLE_PIN);
|
||||
setup_pin(FAILSAFE_TOGGLE_PIN);
|
||||
setup_pin(SCHEDULED_TOGGLE_PIN_1);
|
||||
setup_pin(SCHEDULED_TOGGLE_PIN_2);
|
||||
|
||||
hal.console->printf_P(PSTR("Testing delay callback. "
|
||||
"Pin %d should toggle at 1khz:\r\n"),
|
||||
hal.console->printf_P("Testing delay callback. "
|
||||
"Pin %d should toggle at 1khz:\r\n",
|
||||
(int) DELAY_TOGGLE_PIN);
|
||||
|
||||
// hal.scheduler->register_delay_callback(delay_toggle,0);
|
||||
|
||||
hal.scheduler->delay(2000);
|
||||
hal.console->printf_P(PSTR("Testing failsafe callback. "
|
||||
"Pin %d should toggle at 1khz:\r\n"),
|
||||
hal.console->printf_P("Testing failsafe callback. "
|
||||
"Pin %d should toggle at 1khz:\r\n",
|
||||
(int) FAILSAFE_TOGGLE_PIN);
|
||||
|
||||
hal.scheduler->register_timer_failsafe(failsafe_toggle, 1000);
|
||||
|
||||
hal.scheduler->delay(2000);
|
||||
|
||||
hal.console->printf_P(PSTR("Testing running timer processes.\r\n"));
|
||||
hal.console->printf_P(PSTR("Pin %d should toggle at 1khz.\r\n"),
|
||||
hal.console->printf_P("Testing running timer processes.\r\n");
|
||||
hal.console->printf_P("Pin %d should toggle at 1khz.\r\n",
|
||||
(int) SCHEDULED_TOGGLE_PIN_1);
|
||||
hal.console->printf_P(PSTR("Pin %d should toggle at 1khz.\r\n"),
|
||||
hal.console->printf_P("Pin %d should toggle at 1khz.\r\n",
|
||||
(int) SCHEDULED_TOGGLE_PIN_2);
|
||||
|
||||
hal.scheduler->register_timer_process(schedule_toggle_1);
|
||||
|
@ -97,10 +97,10 @@ void setup (void) {
|
|||
|
||||
// not yet working on flymaple: see FLYMAPLEScheduler::_timer_procs_timer_event()
|
||||
#if 1
|
||||
hal.console->printf_P(PSTR("Test running a pathological timer process.\r\n"
|
||||
hal.console->printf_P("Test running a pathological timer process.\r\n"
|
||||
"Failsafe should continue even as pathological process "
|
||||
"dominates the processor."));
|
||||
hal.console->printf_P(PSTR("Pin %d should toggle then go high forever.\r\n"),
|
||||
"dominates the processor.");
|
||||
hal.console->printf_P("Pin %d should toggle then go high forever.\r\n",
|
||||
(int) SCHEDULED_TOGGLE_PIN_2);
|
||||
hal.scheduler->delay(200);
|
||||
hal.scheduler->register_timer_process(schedule_toggle_hang);
|
||||
|
|
|
@ -53,7 +53,7 @@ void blink_a3() {
|
|||
}
|
||||
|
||||
void setup_pin(int pin_num) {
|
||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||
hal.console->printf_P("Setup pin %d\r\n", pin_num);
|
||||
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||
/* Blink so we can see setup on the logic analyzer.*/
|
||||
hal.gpio->write(pin_num,1);
|
||||
|
@ -61,24 +61,24 @@ void setup_pin(int pin_num) {
|
|||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.console->printf_P(PSTR("Starting Semaphore test\r\n"));
|
||||
hal.console->printf_P("Starting Semaphore test\r\n");
|
||||
|
||||
setup_pin(PIN_A0);
|
||||
setup_pin(PIN_A1);
|
||||
setup_pin(PIN_A2);
|
||||
setup_pin(PIN_A3);
|
||||
|
||||
hal.console->printf_P(PSTR("Using SPIDeviceManager builtin Semaphore\r\n"));
|
||||
hal.console->printf_P("Using SPIDeviceManager builtin Semaphore\r\n");
|
||||
|
||||
AP_HAL::SPIDeviceDriver *dataflash = hal.spi->device(AP_HAL::SPIDevice_Dataflash); // not really
|
||||
|
||||
if (dataflash == NULL) {
|
||||
hal.scheduler->panic(PSTR("Error: No SPIDeviceDriver!"));
|
||||
hal.scheduler->panic("Error: No SPIDeviceDriver!");
|
||||
}
|
||||
|
||||
sem = dataflash->get_semaphore();
|
||||
if (sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("Error: No SPIDeviceDriver semaphore!"));
|
||||
hal.scheduler->panic("Error: No SPIDeviceDriver semaphore!");
|
||||
}
|
||||
|
||||
hal.scheduler->register_timer_process(async_blinker);
|
||||
|
|
|
@ -12,40 +12,40 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
uint8_t fibs[] = { 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 0 };
|
||||
|
||||
void test_erase() {
|
||||
hal.console->printf_P(PSTR("erasing... "));
|
||||
hal.console->printf_P("erasing... ");
|
||||
for(int i = 0; i < 100; i++) {
|
||||
hal.storage->write_byte(i, 0);
|
||||
}
|
||||
hal.console->printf_P(PSTR(" done.\r\n"));
|
||||
hal.console->printf_P(" done.\r\n");
|
||||
}
|
||||
|
||||
void test_write() {
|
||||
hal.console->printf_P(PSTR("writing... "));
|
||||
hal.console->printf_P("writing... ");
|
||||
hal.storage->write_block(0, fibs, sizeof(fibs));
|
||||
hal.console->printf_P(PSTR(" done.\r\n"));
|
||||
hal.console->printf_P(" done.\r\n");
|
||||
}
|
||||
|
||||
void test_readback() {
|
||||
hal.console->printf_P(PSTR("reading back...\r\n"));
|
||||
hal.console->printf_P("reading back...\r\n");
|
||||
uint8_t readback[sizeof(fibs)];
|
||||
bool success = true;
|
||||
hal.storage->read_block(readback, 0, sizeof(fibs));
|
||||
for (int i = 0; i < sizeof(fibs); i++) {
|
||||
if (readback[i] != fibs[i]) {
|
||||
success = false;
|
||||
hal.console->printf_P(PSTR("At index %d expected %d got %d\r\n"),
|
||||
hal.console->printf_P("At index %d expected %d got %d\r\n",
|
||||
i, (int) fibs[i], (int) readback[i]);
|
||||
}
|
||||
}
|
||||
if (success) {
|
||||
hal.console->printf_P(PSTR("all bytes read successfully\r\n"));
|
||||
hal.console->printf_P("all bytes read successfully\r\n");
|
||||
}
|
||||
hal.console->printf_P(PSTR("done reading back.\r\n"));
|
||||
hal.console->printf_P("done reading back.\r\n");
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.scheduler->delay(5000);
|
||||
hal.console->printf_P(PSTR("Starting AP_HAL_FLYMAPLE::Storage test\r\n"));
|
||||
hal.console->printf_P("Starting AP_HAL_FLYMAPLE::Storage test\r\n");
|
||||
|
||||
hal.console->printf("test %d\n", i);
|
||||
test_readback(); // Test what was left from the last run, possibly after power off
|
||||
|
|
|
@ -30,11 +30,11 @@ void setup(void)
|
|||
hal.uartA->println(1000, 8);
|
||||
hal.uartA->println(1000, 10);
|
||||
hal.uartA->println(1000, 16);
|
||||
hal.uartA->println_P(PSTR("progmem"));
|
||||
hal.uartA->println_P("progmem");
|
||||
int x = 3;
|
||||
int *ptr = &x;
|
||||
hal.uartA->printf("printf %d %u %#x %p %f %s\n", -1000, 1000, 1000, ptr, 1.2345, PSTR("progmem"));
|
||||
hal.uartA->printf_P(PSTR("printf_P %d %u %#x %p %f %s\n"), -1000, 1000, 1000, ptr, 1.2345, PSTR("progmem"));
|
||||
hal.uartA->printf("printf %d %u %#x %p %f %s\n", -1000, 1000, 1000, ptr, 1.2345, "progmem");
|
||||
hal.uartA->printf_P("printf_P %d %u %#x %p %f %s\n", -1000, 1000, 1000, ptr, 1.2345, "progmem");
|
||||
hal.uartA->println("done");
|
||||
}
|
||||
|
||||
|
|
|
@ -15,8 +15,8 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
void test_snprintf_P() {
|
||||
char test[40];
|
||||
memset(test,0,40);
|
||||
hal.util->snprintf_P(test, 40, PSTR("hello %d from prog %f %S\r\n"),
|
||||
10, 1.2345, PSTR("progmem"));
|
||||
hal.util->snprintf_P(test, 40, "hello %d from prog %f %S\r\n",
|
||||
10, 1.2345, "progmem");
|
||||
hal.console->write((const uint8_t*)test, strlen(test));
|
||||
|
||||
}
|
||||
|
|
|
@ -10,11 +10,11 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
|
||||
void setup() {
|
||||
hal.scheduler->delay(5000);
|
||||
hal.console->println_P(PSTR("Empty setup"));
|
||||
hal.console->println_P("Empty setup");
|
||||
}
|
||||
void loop()
|
||||
{
|
||||
hal.console->println_P(PSTR("loop"));
|
||||
hal.console->println_P("loop");
|
||||
hal.console->printf("hello %d\n", 1234);
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
|
|
|
@ -25,8 +25,8 @@ void RCInput_Raspilot::init(void*)
|
|||
_spi_sem = _spi->get_semaphore();
|
||||
|
||||
if (_spi_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: RCIutput_Raspilot did not get "
|
||||
"valid SPI semaphore!"));
|
||||
hal.scheduler->panic("PANIC: RCIutput_Raspilot did not get "
|
||||
"valid SPI semaphore!");
|
||||
return; // never reached
|
||||
}
|
||||
|
||||
|
|
|
@ -247,7 +247,7 @@ void RCOutput_Bebop::init(void* dummy)
|
|||
|
||||
_i2c_sem = hal.i2c1->get_semaphore();
|
||||
if (_i2c_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("RCOutput_Bebop: can't get i2c sem"));
|
||||
hal.scheduler->panic("RCOutput_Bebop: can't get i2c sem");
|
||||
return; /* never reached */
|
||||
}
|
||||
|
||||
|
|
|
@ -84,8 +84,8 @@ void RCOutput_PCA9685::init(void* machtnicht)
|
|||
{
|
||||
_i2c_sem = hal.i2c->get_semaphore();
|
||||
if (_i2c_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: RCOutput_PCA9685 did not get "
|
||||
"valid I2C semaphore!"));
|
||||
hal.scheduler->panic("PANIC: RCOutput_PCA9685 did not get "
|
||||
"valid I2C semaphore!");
|
||||
return; /* never reached */
|
||||
}
|
||||
|
||||
|
|
|
@ -28,8 +28,8 @@ void RCOutput_Raspilot::init(void* machtnicht)
|
|||
_spi_sem = _spi->get_semaphore();
|
||||
|
||||
if (_spi_sem == NULL) {
|
||||
hal.scheduler->panic(PSTR("PANIC: RCOutput_Raspilot did not get "
|
||||
"valid SPI semaphore!"));
|
||||
hal.scheduler->panic("PANIC: RCOutput_Raspilot did not get "
|
||||
"valid SPI semaphore!");
|
||||
return; // never reached
|
||||
}
|
||||
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue