mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: params always use set method
This commit is contained in:
parent
d62508b273
commit
b3f09e5573
@ -447,7 +447,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
||||
|
||||
// in the first call here, if a speedup option is specified, overwrite it
|
||||
if (is_equal(last_speedup, -1.0f) && !is_equal(get_speedup(), 1.0f)) {
|
||||
sitl->speedup = get_speedup();
|
||||
sitl->speedup.set(get_speedup());
|
||||
}
|
||||
|
||||
if (!is_equal(last_speedup, float(sitl->speedup)) && sitl->speedup > 0) {
|
||||
@ -1031,7 +1031,7 @@ void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel)
|
||||
body_accel.z += sitl->shove.z;
|
||||
} else {
|
||||
sitl->shove.start_ms = 0;
|
||||
sitl->shove.t = 0;
|
||||
sitl->shove.t.set(0);
|
||||
}
|
||||
}
|
||||
|
||||
@ -1120,7 +1120,7 @@ void Aircraft::add_twist_forces(Vector3f &rot_accel)
|
||||
rot_accel.z += sitl->twist.z;
|
||||
} else {
|
||||
sitl->twist.start_ms = 0;
|
||||
sitl->twist.t = 0;
|
||||
sitl->twist.t.set(0);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -194,8 +194,8 @@ void SIM_Precland::update(const Location &loc, const Vector3d &position)
|
||||
|
||||
void SIM_Precland::set_default_location(float lat, float lon, int16_t yaw) {
|
||||
if (is_zero(_origin_lat) && is_zero(_origin_lon)) {
|
||||
_origin_lat = lat;
|
||||
_origin_lon = lon;
|
||||
_orient_yaw = yaw;
|
||||
_origin_lat.set(lat);
|
||||
_origin_lon.set(lon);
|
||||
_orient_yaw.set(yaw);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user