Plane: Uniformization of severities
Plane uniformization of severities
This commit is contained in:
parent
1b13315092
commit
e18181e5c2
@ -332,7 +332,7 @@ void Plane::one_second_loop()
|
|||||||
void Plane::log_perf_info()
|
void Plane::log_perf_info()
|
||||||
{
|
{
|
||||||
if (scheduler.debug() != 0) {
|
if (scheduler.debug() != 0) {
|
||||||
gcs_send_text_fmt("G_Dt_max=%lu G_Dt_min=%lu\n",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "G_Dt_max=%lu G_Dt_min=%lu\n",
|
||||||
(unsigned long)G_Dt_max,
|
(unsigned long)G_Dt_max,
|
||||||
(unsigned long)G_Dt_min);
|
(unsigned long)G_Dt_min);
|
||||||
}
|
}
|
||||||
@ -769,22 +769,22 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
|
|||||||
#if GEOFENCE_ENABLED == ENABLED
|
#if GEOFENCE_ENABLED == ENABLED
|
||||||
if (g.fence_autoenable == 1) {
|
if (g.fence_autoenable == 1) {
|
||||||
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {
|
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Disable fence failed (autodisable)");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Disable fence failed (autodisable)");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence disabled (autodisable)");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Fence disabled (autodisable)");
|
||||||
}
|
}
|
||||||
} else if (g.fence_autoenable == 2) {
|
} else if (g.fence_autoenable == 2) {
|
||||||
if (! geofence_set_floor_enabled(false)) {
|
if (! geofence_set_floor_enabled(false)) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Disable fence floor failed (autodisable)");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Disable fence floor failed (autodisable)");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence floor disabled (auto disable)");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Fence floor disabled (auto disable)");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
|
case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
|
||||||
gcs_send_text_fmt("Landing aborted via throttle, climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
|
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted via throttle, climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
|
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
|
||||||
|
@ -609,7 +609,7 @@ bool Plane::suppress_throttle(void)
|
|||||||
if (relative_altitude_abs_cm() >= 1000) {
|
if (relative_altitude_abs_cm() >= 1000) {
|
||||||
// we're more than 10m from the home altitude
|
// we're more than 10m from the home altitude
|
||||||
throttle_suppressed = false;
|
throttle_suppressed = false;
|
||||||
gcs_send_text_fmt("Throttle enabled - altitude %.2f",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled - altitude %.2f",
|
||||||
(double)(relative_altitude_abs_cm()*0.01f));
|
(double)(relative_altitude_abs_cm()*0.01f));
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -620,7 +620,7 @@ bool Plane::suppress_throttle(void)
|
|||||||
// groundspeed with bad GPS reception
|
// groundspeed with bad GPS reception
|
||||||
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
|
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
|
||||||
// we're moving at more than 5 m/s
|
// we're moving at more than 5 m/s
|
||||||
gcs_send_text_fmt("Throttle enabled - speed %.2f airspeed %.2f",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled - speed %.2f airspeed %.2f",
|
||||||
(double)gps.ground_speed(),
|
(double)gps.ground_speed(),
|
||||||
(double)airspeed.get_airspeed());
|
(double)airspeed.get_airspeed());
|
||||||
throttle_suppressed = false;
|
throttle_suppressed = false;
|
||||||
@ -1061,7 +1061,7 @@ void Plane::set_servos(void)
|
|||||||
void Plane::demo_servos(uint8_t i)
|
void Plane::demo_servos(uint8_t i)
|
||||||
{
|
{
|
||||||
while(i > 0) {
|
while(i > 0) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"Demo Servos!");
|
gcs_send_text(MAV_SEVERITY_INFO,"Demo Servos!");
|
||||||
demoing_servos = true;
|
demoing_servos = true;
|
||||||
servo_write(1, 1400);
|
servo_write(1, 1400);
|
||||||
hal.scheduler->delay(400);
|
hal.scheduler->delay(400);
|
||||||
|
@ -1135,7 +1135,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
||||||
|
|
||||||
// do command
|
// do command
|
||||||
send_text(MAV_SEVERITY_WARNING,"command received: ");
|
send_text(MAV_SEVERITY_INFO,"command received: ");
|
||||||
|
|
||||||
switch(packet.command) {
|
switch(packet.command) {
|
||||||
|
|
||||||
@ -1386,9 +1386,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
plane.auto_state.commanded_go_around = true;
|
plane.auto_state.commanded_go_around = true;
|
||||||
|
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Go around command accepted.");
|
plane.gcs_send_text(MAV_SEVERITY_INFO,"Go around command accepted.");
|
||||||
} else {
|
} else {
|
||||||
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Rejected go around command.");
|
plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Rejected go around command.");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -1412,7 +1412,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
if (! plane.geofence_set_floor_enabled(false)) {
|
if (! plane.geofence_set_floor_enabled(false)) {
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
} else {
|
} else {
|
||||||
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Fence floor disabled.");
|
plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Fence floor disabled.");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -1454,7 +1454,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
plane.Log_Write_Home_And_Origin();
|
plane.Log_Write_Home_And_Origin();
|
||||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
plane.gcs_send_text_fmt("set home to %.6f %.6f at %um",
|
plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "set home to %.6f %.6f at %um",
|
||||||
(double)(new_home_loc.lat*1.0e-7f),
|
(double)(new_home_loc.lat*1.0e-7f),
|
||||||
(double)(new_home_loc.lng*1.0e-7f),
|
(double)(new_home_loc.lng*1.0e-7f),
|
||||||
(uint32_t)(new_home_loc.alt*0.01f));
|
(uint32_t)(new_home_loc.alt*0.01f));
|
||||||
@ -1487,10 +1487,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
case PARACHUTE_RELEASE:
|
case PARACHUTE_RELEASE:
|
||||||
// treat as a manual release which performs some additional check of altitude
|
// treat as a manual release which performs some additional check of altitude
|
||||||
if (plane.parachute.released()) {
|
if (plane.parachute.released()) {
|
||||||
plane.gcs_send_text_fmt("Parachute already released");
|
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Parachute already released");
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
} else if (!plane.parachute.enabled()) {
|
} else if (!plane.parachute.enabled()) {
|
||||||
plane.gcs_send_text_fmt("Parachute not enabled");
|
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Parachute not enabled");
|
||||||
result = MAV_RESULT_FAILED;
|
result = MAV_RESULT_FAILED;
|
||||||
} else {
|
} else {
|
||||||
if (!plane.parachute_manual_release()) {
|
if (!plane.parachute_manual_release()) {
|
||||||
@ -1550,10 +1550,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||||
{
|
{
|
||||||
// mark the firmware version in the tlog
|
// mark the firmware version in the tlog
|
||||||
send_text(MAV_SEVERITY_WARNING, FIRMWARE_STRING);
|
send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING);
|
||||||
|
|
||||||
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
|
||||||
send_text(MAV_SEVERITY_WARNING, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||||
#endif
|
#endif
|
||||||
handle_param_request_list(msg);
|
handle_param_request_list(msg);
|
||||||
break;
|
break;
|
||||||
@ -1893,7 +1893,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
||||||
plane.Log_Write_Home_And_Origin();
|
plane.Log_Write_Home_And_Origin();
|
||||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||||
plane.gcs_send_text_fmt("set home to %.6f %.6f at %um",
|
plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "set home to %.6f %.6f at %um",
|
||||||
(double)(new_home_loc.lat*1.0e-7f),
|
(double)(new_home_loc.lat*1.0e-7f),
|
||||||
(double)(new_home_loc.lng*1.0e-7f),
|
(double)(new_home_loc.lng*1.0e-7f),
|
||||||
(uint32_t)(new_home_loc.alt*0.01f));
|
(uint32_t)(new_home_loc.alt*0.01f));
|
||||||
@ -1929,7 +1929,7 @@ void Plane::mavlink_delay_cb()
|
|||||||
}
|
}
|
||||||
if (tnow - last_5s > 5000) {
|
if (tnow - last_5s > 5000) {
|
||||||
last_5s = tnow;
|
last_5s = tnow;
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "Initialising APM...");
|
gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM...");
|
||||||
}
|
}
|
||||||
check_usb_mux();
|
check_usb_mux();
|
||||||
|
|
||||||
@ -2006,10 +2006,10 @@ void Plane::gcs_send_text(MAV_SEVERITY severity, const char *str)
|
|||||||
* only one fits in the queue, so if you send more than one before the
|
* only one fits in the queue, so if you send more than one before the
|
||||||
* last one gets into the serial buffer then the old one will be lost
|
* last one gets into the serial buffer then the old one will be lost
|
||||||
*/
|
*/
|
||||||
void Plane::gcs_send_text_fmt(const char *fmt, ...)
|
void Plane::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
|
||||||
{
|
{
|
||||||
va_list arg_list;
|
va_list arg_list;
|
||||||
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
|
gcs[0].pending_status.severity = (uint8_t)severity;
|
||||||
va_start(arg_list, fmt);
|
va_start(arg_list, fmt);
|
||||||
hal.util->vsnprintf((char *)gcs[0].pending_status.text,
|
hal.util->vsnprintf((char *)gcs[0].pending_status.text,
|
||||||
sizeof(gcs[0].pending_status.text), fmt, arg_list);
|
sizeof(gcs[0].pending_status.text), fmt, arg_list);
|
||||||
|
@ -916,7 +916,7 @@ private:
|
|||||||
void update_aux();
|
void update_aux();
|
||||||
void update_is_flying_5Hz(void);
|
void update_is_flying_5Hz(void);
|
||||||
void crash_detection_update(void);
|
void crash_detection_update(void);
|
||||||
void gcs_send_text_fmt(const char *fmt, ...);
|
void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...);
|
||||||
void handle_auto_mode(void);
|
void handle_auto_mode(void);
|
||||||
void calc_throttle();
|
void calc_throttle();
|
||||||
void calc_nav_roll();
|
void calc_nav_roll();
|
||||||
|
@ -578,7 +578,7 @@ void Plane::rangefinder_height_update(void)
|
|||||||
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH &&
|
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH &&
|
||||||
g.rangefinder_landing) {
|
g.rangefinder_landing) {
|
||||||
rangefinder_state.in_use = true;
|
rangefinder_state.in_use = true;
|
||||||
gcs_send_text_fmt("Rangefinder engaged at %.2fm", height_estimate);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Rangefinder engaged at %.2fm", height_estimate);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
@ -610,7 +610,7 @@ void Plane::rangefinder_height_update(void)
|
|||||||
if (fabsf(rangefinder_state.correction - rangefinder_state.initial_correction) > 30) {
|
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
|
// the correction has changed by more than 30m, reset use of Lidar. We may have a bad lidar
|
||||||
if (rangefinder_state.in_use) {
|
if (rangefinder_state.in_use) {
|
||||||
gcs_send_text_fmt("Rangefinder disengaged at %.2fm", height_estimate);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Rangefinder disengaged at %.2fm", height_estimate);
|
||||||
}
|
}
|
||||||
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
|
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
|
||||||
}
|
}
|
||||||
|
@ -52,7 +52,7 @@ void Plane::set_next_WP(const struct Location &loc)
|
|||||||
// location as the previous waypoint, to prevent immediately
|
// location as the previous waypoint, to prevent immediately
|
||||||
// considering the waypoint complete
|
// considering the waypoint complete
|
||||||
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "Resetting prev_WP");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting prev_WP");
|
||||||
prev_WP_loc = current_loc;
|
prev_WP_loc = current_loc;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -100,14 +100,14 @@ void Plane::set_guided_WP(void)
|
|||||||
// -------------------------------
|
// -------------------------------
|
||||||
void Plane::init_home()
|
void Plane::init_home()
|
||||||
{
|
{
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "init home");
|
gcs_send_text(MAV_SEVERITY_INFO, "init home");
|
||||||
|
|
||||||
ahrs.set_home(gps.location());
|
ahrs.set_home(gps.location());
|
||||||
home_is_set = HOME_SET_NOT_LOCKED;
|
home_is_set = HOME_SET_NOT_LOCKED;
|
||||||
Log_Write_Home_And_Origin();
|
Log_Write_Home_And_Origin();
|
||||||
GCS_MAVLINK::send_home_all(gps.location());
|
GCS_MAVLINK::send_home_all(gps.location());
|
||||||
|
|
||||||
gcs_send_text_fmt("gps alt: %lu", (unsigned long)home.alt);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "gps alt: %lu", (unsigned long)home.alt);
|
||||||
|
|
||||||
// Save Home to EEPROM
|
// Save Home to EEPROM
|
||||||
mission.write_home_to_storage();
|
mission.write_home_to_storage();
|
||||||
|
@ -34,9 +34,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
// reset loiter start time. New command is a new loiter
|
// reset loiter start time. New command is a new loiter
|
||||||
loiter.start_time_ms = 0;
|
loiter.start_time_ms = 0;
|
||||||
|
|
||||||
gcs_send_text_fmt("Executing nav command ID #%i",cmd.id);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing nav command ID #%i",cmd.id);
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt("Executing command ID #%i",cmd.id);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing command ID #%i",cmd.id);
|
||||||
}
|
}
|
||||||
|
|
||||||
switch(cmd.id) {
|
switch(cmd.id) {
|
||||||
@ -127,7 +127,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
case MAV_CMD_DO_INVERTED_FLIGHT:
|
case MAV_CMD_DO_INVERTED_FLIGHT:
|
||||||
if (cmd.p1 == 0 || cmd.p1 == 1) {
|
if (cmd.p1 == 0 || cmd.p1 == 1) {
|
||||||
auto_state.inverted_flight = (bool)cmd.p1;
|
auto_state.inverted_flight = (bool)cmd.p1;
|
||||||
gcs_send_text_fmt("Set inverted %u", cmd.p1);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -140,15 +140,15 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
#if GEOFENCE_ENABLED == ENABLED
|
#if GEOFENCE_ENABLED == ENABLED
|
||||||
if (cmd.p1 != 2) {
|
if (cmd.p1 != 2) {
|
||||||
if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) {
|
if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) {
|
||||||
gcs_send_text_fmt("Unable to set fence enabled state to %u", cmd.p1);
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to set fence enabled state to %u", cmd.p1);
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt("Set fence enabled state to %u", cmd.p1);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set fence enabled state to %u", cmd.p1);
|
||||||
}
|
}
|
||||||
} else { //commanding to only disable floor
|
} else { //commanding to only disable floor
|
||||||
if (! geofence_set_floor_enabled(false)) {
|
if (! geofence_set_floor_enabled(false)) {
|
||||||
gcs_send_text_fmt("Unabled to disable fence floor.\n");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unabled to disable fence floor.\n");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt("Fence floor disabled.\n");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Fence floor disabled.\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -294,9 +294,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
|||||||
default:
|
default:
|
||||||
// error message
|
// error message
|
||||||
if (AP_Mission::is_nav_cmd(cmd)) {
|
if (AP_Mission::is_nav_cmd(cmd)) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_nav: Invalid or no current Nav cmd");
|
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: Invalid or no current Nav cmd");
|
||||||
}else{
|
}else{
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_conditon: Invalid or no current Condition cmd");
|
gcs_send_text(MAV_SEVERITY_WARNING,"verify_conditon: Invalid or no current Condition cmd");
|
||||||
}
|
}
|
||||||
// return true so that we do not get stuck at this command
|
// return true so that we do not get stuck at this command
|
||||||
return true;
|
return true;
|
||||||
@ -494,7 +494,7 @@ bool Plane::verify_takeoff()
|
|||||||
float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01f)) - steer_state.locked_course_err;
|
float takeoff_course = wrap_PI(radians(gps.ground_course_cd()*0.01f)) - steer_state.locked_course_err;
|
||||||
takeoff_course = wrap_PI(takeoff_course);
|
takeoff_course = wrap_PI(takeoff_course);
|
||||||
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
|
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
|
||||||
gcs_send_text_fmt("Holding course %ld at %.1fm/s (%.1f)",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Holding course %ld at %.1fm/s (%.1f)",
|
||||||
steer_state.hold_course_cd,
|
steer_state.hold_course_cd,
|
||||||
(double)gps.ground_speed(),
|
(double)gps.ground_speed(),
|
||||||
(double)degrees(steer_state.locked_course_err));
|
(double)degrees(steer_state.locked_course_err));
|
||||||
@ -511,7 +511,7 @@ bool Plane::verify_takeoff()
|
|||||||
// see if we have reached takeoff altitude
|
// see if we have reached takeoff altitude
|
||||||
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
|
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
|
||||||
if (relative_alt_cm > auto_state.takeoff_altitude_rel_cm) {
|
if (relative_alt_cm > auto_state.takeoff_altitude_rel_cm) {
|
||||||
gcs_send_text_fmt("Takeoff complete at %.2fm",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
|
||||||
(double)(relative_alt_cm*0.01f));
|
(double)(relative_alt_cm*0.01f));
|
||||||
steer_state.hold_course_cd = -1;
|
steer_state.hold_course_cd = -1;
|
||||||
auto_state.takeoff_complete = true;
|
auto_state.takeoff_complete = true;
|
||||||
@ -520,9 +520,9 @@ bool Plane::verify_takeoff()
|
|||||||
#if GEOFENCE_ENABLED == ENABLED
|
#if GEOFENCE_ENABLED == ENABLED
|
||||||
if (g.fence_autoenable > 0) {
|
if (g.fence_autoenable > 0) {
|
||||||
if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
|
if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Enable fence failed (cannot autoenable");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "Enable fence failed (cannot autoenable");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence enabled. (autoenabled)");
|
gcs_send_text(MAV_SEVERITY_INFO, "Fence enabled. (autoenabled)");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -567,7 +567,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (auto_state.wp_distance <= acceptance_distance) {
|
if (auto_state.wp_distance <= acceptance_distance) {
|
||||||
gcs_send_text_fmt("Reached Waypoint #%i dist %um",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Waypoint #%i dist %um",
|
||||||
(unsigned)mission.get_current_nav_cmd().index,
|
(unsigned)mission.get_current_nav_cmd().index,
|
||||||
(unsigned)get_distance(current_loc, next_WP_loc));
|
(unsigned)get_distance(current_loc, next_WP_loc));
|
||||||
return true;
|
return true;
|
||||||
@ -575,7 +575,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
// have we flown past the waypoint?
|
// have we flown past the waypoint?
|
||||||
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
||||||
gcs_send_text_fmt("Passed Waypoint #%i dist %um",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed Waypoint #%i dist %um",
|
||||||
(unsigned)mission.get_current_nav_cmd().index,
|
(unsigned)mission.get_current_nav_cmd().index,
|
||||||
(unsigned)get_distance(current_loc, next_WP_loc));
|
(unsigned)get_distance(current_loc, next_WP_loc));
|
||||||
return true;
|
return true;
|
||||||
@ -694,7 +694,7 @@ bool Plane::verify_RTL()
|
|||||||
update_loiter();
|
update_loiter();
|
||||||
if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) ||
|
if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) ||
|
||||||
nav_controller->reached_loiter_target()) {
|
nav_controller->reached_loiter_target()) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"Reached home");
|
gcs_send_text(MAV_SEVERITY_INFO,"Reached home");
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
@ -744,11 +744,11 @@ bool Plane::verify_continue_and_change_alt()
|
|||||||
bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
|
bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
|
||||||
{
|
{
|
||||||
if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) {
|
if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"Reached altitude");
|
gcs_send_text(MAV_SEVERITY_INFO,"Reached altitude");
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
|
if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
|
||||||
gcs_send_text_fmt("Reached descent rate %.1f m/s", (double)auto_state.sink_rate);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)auto_state.sink_rate);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -854,17 +854,17 @@ void Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
|||||||
case 0: // Airspeed
|
case 0: // Airspeed
|
||||||
if (cmd.content.speed.target_ms > 0) {
|
if (cmd.content.speed.target_ms > 0) {
|
||||||
g.airspeed_cruise_cm.set(cmd.content.speed.target_ms * 100);
|
g.airspeed_cruise_cm.set(cmd.content.speed.target_ms * 100);
|
||||||
gcs_send_text_fmt("Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 1: // Ground speed
|
case 1: // Ground speed
|
||||||
gcs_send_text_fmt("Set groundspeed %u", (unsigned)cmd.content.speed.target_ms);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)cmd.content.speed.target_ms);
|
||||||
g.min_gndspeed_cm.set(cmd.content.speed.target_ms * 100);
|
g.min_gndspeed_cm.set(cmd.content.speed.target_ms * 100);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
|
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
|
||||||
gcs_send_text_fmt("Set throttle %u", (unsigned)cmd.content.speed.throttle_pct);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)cmd.content.speed.throttle_pct);
|
||||||
aparm.throttle_cruise.set(cmd.content.speed.throttle_pct);
|
aparm.throttle_cruise.set(cmd.content.speed.throttle_pct);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -982,7 +982,7 @@ bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
|
|||||||
void Plane::exit_mission_callback()
|
void Plane::exit_mission_callback()
|
||||||
{
|
{
|
||||||
if (control_mode == AUTO) {
|
if (control_mode == AUTO) {
|
||||||
gcs_send_text_fmt("Returning to Home");
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Returning to Home");
|
||||||
memset(&auto_rtl_command, 0, sizeof(auto_rtl_command));
|
memset(&auto_rtl_command, 0, sizeof(auto_rtl_command));
|
||||||
auto_rtl_command.content.location =
|
auto_rtl_command.content.location =
|
||||||
rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude());
|
rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude());
|
||||||
|
@ -46,7 +46,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
gcs_send_text_fmt("flight mode = %u", (unsigned)control_mode);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "flight mode = %u", (unsigned)control_mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::failsafe_long_on_event(enum failsafe_state fstype)
|
void Plane::failsafe_long_on_event(enum failsafe_state fstype)
|
||||||
@ -91,7 +91,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype)
|
|||||||
if (fstype == FAILSAFE_GCS) {
|
if (fstype == FAILSAFE_GCS) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "No GCS heartbeat.");
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "No GCS heartbeat.");
|
||||||
}
|
}
|
||||||
gcs_send_text_fmt("flight mode = %u", (unsigned)control_mode);
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "flight mode = %u", (unsigned)control_mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::failsafe_short_off_event()
|
void Plane::failsafe_short_off_event()
|
||||||
@ -113,7 +113,7 @@ void Plane::low_battery_event(void)
|
|||||||
if (failsafe.low_battery) {
|
if (failsafe.low_battery) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
gcs_send_text_fmt("Low Battery %.2fV Used %.0f mAh",
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Low Battery %.2fV Used %.0f mAh",
|
||||||
(double)battery.voltage(), (double)battery.current_total_mah());
|
(double)battery.voltage(), (double)battery.current_total_mah());
|
||||||
if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
|
if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
|
||||||
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||||
|
@ -137,13 +137,13 @@ void Plane::geofence_load(void)
|
|||||||
geofence_state->boundary_uptodate = true;
|
geofence_state->boundary_uptodate = true;
|
||||||
geofence_state->fence_triggered = false;
|
geofence_state->fence_triggered = false;
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence loaded");
|
gcs_send_text(MAV_SEVERITY_INFO,"geo-fence loaded");
|
||||||
gcs_send_message(MSG_FENCE_STATUS);
|
gcs_send_message(MSG_FENCE_STATUS);
|
||||||
return;
|
return;
|
||||||
|
|
||||||
failed:
|
failed:
|
||||||
g.fence_action.set(FENCE_ACTION_NONE);
|
g.fence_action.set(FENCE_ACTION_NONE);
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"geo-fence setup error");
|
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence setup error");
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -335,7 +335,7 @@ void Plane::geofence_check(bool altitude_check_only)
|
|||||||
if (geofence_state->fence_triggered && !altitude_check_only) {
|
if (geofence_state->fence_triggered && !altitude_check_only) {
|
||||||
// we have moved back inside the fence
|
// we have moved back inside the fence
|
||||||
geofence_state->fence_triggered = false;
|
geofence_state->fence_triggered = false;
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence OK");
|
gcs_send_text(MAV_SEVERITY_INFO,"geo-fence OK");
|
||||||
#if FENCE_TRIGGERED_PIN > 0
|
#if FENCE_TRIGGERED_PIN > 0
|
||||||
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
|
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);
|
hal.gpio->write(FENCE_TRIGGERED_PIN, 1);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence triggered");
|
gcs_send_text(MAV_SEVERITY_NOTICE,"geo-fence triggered");
|
||||||
gcs_send_message(MSG_FENCE_STATUS);
|
gcs_send_message(MSG_FENCE_STATUS);
|
||||||
|
|
||||||
// see what action the user wants
|
// see what action the user wants
|
||||||
|
@ -226,7 +226,7 @@ void Plane::crash_detection_update(void)
|
|||||||
if (crashed_near_land_waypoint) {
|
if (crashed_near_land_waypoint) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken");
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Crash Detected - no action taken");
|
gcs_send_text(MAV_SEVERITY_EMERGENCY, "Crash Detected - no action taken");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
@ -237,7 +237,7 @@ void Plane::crash_detection_update(void)
|
|||||||
if (crashed_near_land_waypoint) {
|
if (crashed_near_land_waypoint) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected");
|
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected");
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Crash Detected");
|
gcs_send_text(MAV_SEVERITY_EMERGENCY, "Crash Detected");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -74,9 +74,9 @@ bool Plane::verify_land()
|
|||||||
if (!auto_state.land_complete) {
|
if (!auto_state.land_complete) {
|
||||||
auto_state.post_landing_stats = true;
|
auto_state.post_landing_stats = true;
|
||||||
if (!is_flying() && (millis()-auto_state.last_flying_ms) > 3000) {
|
if (!is_flying() && (millis()-auto_state.last_flying_ms) > 3000) {
|
||||||
gcs_send_text_fmt("Flare crash detected: speed=%.1f", (double)gps.ground_speed());
|
gcs_send_text_fmt(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)gps.ground_speed());
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt("Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
|
||||||
(double)height, (double)auto_state.sink_rate,
|
(double)height, (double)auto_state.sink_rate,
|
||||||
(double)gps.ground_speed(),
|
(double)gps.ground_speed(),
|
||||||
(double)get_distance(current_loc, next_WP_loc));
|
(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
|
// 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()) {
|
if (auto_state.post_landing_stats && !arming.is_armed()) {
|
||||||
auto_state.post_landing_stats = false;
|
auto_state.post_landing_stats = false;
|
||||||
gcs_send_text_fmt("Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
|
||||||
}
|
}
|
||||||
|
|
||||||
// check if we should auto-disarm after a confirmed landing
|
// 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 */
|
/* we have auto disarm enabled. See if enough time has passed */
|
||||||
if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
|
if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
|
||||||
if (disarm_motors()) {
|
if (disarm_motors()) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"Auto-Disarmed");
|
gcs_send_text(MAV_SEVERITY_INFO,"Auto-Disarmed");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -260,14 +260,14 @@ bool Plane::restart_landing_sequence()
|
|||||||
mission.set_current_cmd(current_index+1))
|
mission.set_current_cmd(current_index+1))
|
||||||
{
|
{
|
||||||
// if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it
|
// if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it
|
||||||
gcs_send_text_fmt("Restarted landing sequence climbing to %dm", cmd.content.location.alt/100);
|
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence climbing to %dm", cmd.content.location.alt/100);
|
||||||
success = true;
|
success = true;
|
||||||
}
|
}
|
||||||
else if (do_land_start_index != 0 &&
|
else if (do_land_start_index != 0 &&
|
||||||
mission.set_current_cmd(do_land_start_index))
|
mission.set_current_cmd(do_land_start_index))
|
||||||
{
|
{
|
||||||
// look for a DO_LAND_START and use that index
|
// look for a DO_LAND_START and use that index
|
||||||
gcs_send_text_fmt("Restarted landing via DO_LAND_START: %d",do_land_start_index);
|
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing via DO_LAND_START: %d",do_land_start_index);
|
||||||
success = true;
|
success = true;
|
||||||
}
|
}
|
||||||
else if (prev_cmd_with_wp_index != AP_MISSION_CMD_INDEX_NONE &&
|
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
|
// 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
|
// repeat that cmd to restart the landing from the top of approach to repeat intended glide slope
|
||||||
gcs_send_text_fmt("Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
|
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
|
||||||
success = true;
|
success = true;
|
||||||
} else {
|
} else {
|
||||||
gcs_send_text_fmt("Unable to restart landing sequence!");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to restart landing sequence!");
|
||||||
success = false;
|
success = false;
|
||||||
}
|
}
|
||||||
return success;
|
return success;
|
||||||
@ -301,12 +301,12 @@ bool Plane::jump_to_landing_sequence(void)
|
|||||||
mission.resume();
|
mission.resume();
|
||||||
}
|
}
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "Landing sequence begun.");
|
gcs_send_text(MAV_SEVERITY_INFO, "Landing sequence begun.");
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "Unable to start landing sequence.");
|
gcs_send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence.");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -47,7 +47,7 @@ bool Plane::parachute_manual_release()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (relative_altitude() < parachute.alt_min()) {
|
if (relative_altitude() < parachute.alt_min()) {
|
||||||
gcs_send_text_fmt("Parachute: too low");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Parachute: too low");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -239,7 +239,7 @@ void Plane::control_failsafe(uint16_t pwm)
|
|||||||
// throttle has dropped below the mark
|
// throttle has dropped below the mark
|
||||||
failsafe.ch3_counter++;
|
failsafe.ch3_counter++;
|
||||||
if (failsafe.ch3_counter == 10) {
|
if (failsafe.ch3_counter == 10) {
|
||||||
gcs_send_text_fmt("MSG FS ON %u", (unsigned)pwm);
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS ON %u", (unsigned)pwm);
|
||||||
failsafe.ch3_failsafe = true;
|
failsafe.ch3_failsafe = true;
|
||||||
AP_Notify::flags.failsafe_radio = true;
|
AP_Notify::flags.failsafe_radio = true;
|
||||||
}
|
}
|
||||||
@ -255,7 +255,7 @@ void Plane::control_failsafe(uint16_t pwm)
|
|||||||
failsafe.ch3_counter = 3;
|
failsafe.ch3_counter = 3;
|
||||||
}
|
}
|
||||||
if (failsafe.ch3_counter == 1) {
|
if (failsafe.ch3_counter == 1) {
|
||||||
gcs_send_text_fmt("MSG FS OFF %u", (unsigned)pwm);
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "MSG FS OFF %u", (unsigned)pwm);
|
||||||
} else if(failsafe.ch3_counter == 0) {
|
} else if(failsafe.ch3_counter == 0) {
|
||||||
failsafe.ch3_failsafe = false;
|
failsafe.ch3_failsafe = false;
|
||||||
AP_Notify::flags.failsafe_radio = false;
|
AP_Notify::flags.failsafe_radio = false;
|
||||||
|
@ -5,10 +5,10 @@
|
|||||||
|
|
||||||
void Plane::init_barometer(void)
|
void Plane::init_barometer(void)
|
||||||
{
|
{
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "Calibrating barometer");
|
gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
|
||||||
barometer.calibrate();
|
barometer.calibrate();
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "barometer calibration complete");
|
gcs_send_text(MAV_SEVERITY_INFO, "barometer calibration complete");
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::init_rangefinder(void)
|
void Plane::init_rangefinder(void)
|
||||||
@ -98,7 +98,7 @@ void Plane::zero_airspeed(bool in_startup)
|
|||||||
read_airspeed();
|
read_airspeed();
|
||||||
// update barometric calibration with new airspeed supplied temperature
|
// update barometric calibration with new airspeed supplied temperature
|
||||||
barometer.update_calibration();
|
barometer.update_calibration();
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"zero airspeed calibrated");
|
gcs_send_text(MAV_SEVERITY_INFO,"zero airspeed calibrated");
|
||||||
}
|
}
|
||||||
|
|
||||||
// read_battery - reads battery voltage and current and invokes failsafe
|
// read_battery - reads battery voltage and current and invokes failsafe
|
||||||
|
@ -254,10 +254,10 @@ void Plane::startup_ground(void)
|
|||||||
{
|
{
|
||||||
set_mode(INITIALISING);
|
set_mode(INITIALISING);
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
|
gcs_send_text(MAV_SEVERITY_INFO,"<startup_ground> GROUND START");
|
||||||
|
|
||||||
#if (GROUND_START_DELAY > 0)
|
#if (GROUND_START_DELAY > 0)
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
|
gcs_send_text(MAV_SEVERITY_NOTICE,"<startup_ground> With Delay");
|
||||||
delay(GROUND_START_DELAY * 1000);
|
delay(GROUND_START_DELAY * 1000);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -304,7 +304,7 @@ void Plane::startup_ground(void)
|
|||||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||||
ins.set_dataflash(&DataFlash);
|
ins.set_dataflash(&DataFlash);
|
||||||
|
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING,"\n\n Ready to FLY.");
|
gcs_send_text(MAV_SEVERITY_INFO,"\n\n Ready to FLY.");
|
||||||
}
|
}
|
||||||
|
|
||||||
enum FlightMode Plane::get_previous_mode() {
|
enum FlightMode Plane::get_previous_mode() {
|
||||||
|
@ -22,7 +22,7 @@ bool Plane::auto_takeoff_check(void)
|
|||||||
|
|
||||||
// Reset states if process has been interrupted
|
// Reset states if process has been interrupted
|
||||||
if (last_check_ms && (now - last_check_ms) > 200) {
|
if (last_check_ms && (now - last_check_ms) > 200) {
|
||||||
gcs_send_text_fmt("Timer Interrupted AUTO");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Timer Interrupted AUTO");
|
||||||
launchTimerStarted = false;
|
launchTimerStarted = false;
|
||||||
last_tkoff_arm_time = 0;
|
last_tkoff_arm_time = 0;
|
||||||
last_check_ms = now;
|
last_check_ms = now;
|
||||||
@ -48,13 +48,13 @@ bool Plane::auto_takeoff_check(void)
|
|||||||
if (!launchTimerStarted) {
|
if (!launchTimerStarted) {
|
||||||
launchTimerStarted = true;
|
launchTimerStarted = true;
|
||||||
last_tkoff_arm_time = now;
|
last_tkoff_arm_time = now;
|
||||||
gcs_send_text_fmt("Armed AUTO, xaccel = %.1f m/s/s, waiting %.1f sec",
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Armed AUTO, xaccel = %.1f m/s/s, waiting %.1f sec",
|
||||||
(double)SpdHgt_Controller->get_VXdot(), (double)(wait_time_ms*0.001f));
|
(double)SpdHgt_Controller->get_VXdot(), (double)(wait_time_ms*0.001f));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Only perform velocity check if not timed out
|
// Only perform velocity check if not timed out
|
||||||
if ((now - last_tkoff_arm_time) > wait_time_ms+100U) {
|
if ((now - last_tkoff_arm_time) > wait_time_ms+100U) {
|
||||||
gcs_send_text_fmt("Timeout AUTO");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Timeout AUTO");
|
||||||
goto no_launch;
|
goto no_launch;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -62,14 +62,14 @@ bool Plane::auto_takeoff_check(void)
|
|||||||
if (ahrs.pitch_sensor <= -3000 ||
|
if (ahrs.pitch_sensor <= -3000 ||
|
||||||
ahrs.pitch_sensor >= 4500 ||
|
ahrs.pitch_sensor >= 4500 ||
|
||||||
labs(ahrs.roll_sensor) > 3000) {
|
labs(ahrs.roll_sensor) > 3000) {
|
||||||
gcs_send_text_fmt("Bad Launch AUTO");
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad Launch AUTO");
|
||||||
goto no_launch;
|
goto no_launch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check ground speed and time delay
|
// Check ground speed and time delay
|
||||||
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || is_zero(g.takeoff_throttle_min_speed))) &&
|
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || is_zero(g.takeoff_throttle_min_speed))) &&
|
||||||
((now - last_tkoff_arm_time) >= wait_time_ms)) {
|
((now - last_tkoff_arm_time) >= wait_time_ms)) {
|
||||||
gcs_send_text_fmt("Triggered AUTO, GPSspd = %.1f", (double)gps.ground_speed());
|
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Triggered AUTO, GPSspd = %.1f", (double)gps.ground_speed());
|
||||||
launchTimerStarted = false;
|
launchTimerStarted = false;
|
||||||
last_tkoff_arm_time = 0;
|
last_tkoff_arm_time = 0;
|
||||||
return true;
|
return true;
|
||||||
@ -179,7 +179,7 @@ int8_t Plane::takeoff_tail_hold(void)
|
|||||||
|
|
||||||
return_zero:
|
return_zero:
|
||||||
if (auto_state.fbwa_tdrag_takeoff_mode) {
|
if (auto_state.fbwa_tdrag_takeoff_mode) {
|
||||||
gcs_send_text(MAV_SEVERITY_WARNING, "FBWA tdrag off");
|
gcs_send_text(MAV_SEVERITY_NOTICE, "FBWA tdrag off");
|
||||||
auto_state.fbwa_tdrag_takeoff_mode = false;
|
auto_state.fbwa_tdrag_takeoff_mode = false;
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user