mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed build with no GCS
This commit is contained in:
parent
0700ca4882
commit
32bda36908
|
@ -565,7 +565,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
|||
// constrain height to the ground
|
||||
if (on_ground()) {
|
||||
if (!was_on_ground && AP_HAL::millis() - last_ground_contact_ms > 1000) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "SIM Hit ground at %f m/s", velocity_ef.z);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM Hit ground at %f m/s", velocity_ef.z);
|
||||
last_ground_contact_ms = AP_HAL::millis();
|
||||
}
|
||||
position.z = -(ground_level + frame_height - home.alt * 0.01f + ground_height_difference());
|
||||
|
|
|
@ -54,7 +54,7 @@ void Parachute::update(const struct sitl_input &input)
|
|||
if (pwm >= 1250) {
|
||||
if (!deployed_ms) {
|
||||
deployed_ms = AP_HAL::millis();
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "BANG! Parachute deployed");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "BANG! Parachute deployed");
|
||||
}
|
||||
}
|
||||
last_update_us = now;
|
||||
|
|
|
@ -32,7 +32,7 @@ bool RF_LightWareSerial::check_synced()
|
|||
ssize_t n = read_from_autopilot(buffer, ARRAY_SIZE(buffer) - 1);
|
||||
if (n > 0) {
|
||||
if (!strncmp(buffer, "www\r\n", ARRAY_SIZE(buffer))) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Slurped a sync thing\n");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Slurped a sync thing\n");
|
||||
synced = true;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -94,7 +94,7 @@ void RF_Wasp::check_configuration()
|
|||
}
|
||||
}
|
||||
if (!set) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Wasp: unknown setting (%s)", &_buffer[0]);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Wasp: unknown setting (%s)", &_buffer[0]);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue