mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: remove separate calls to get delta-times for vel and ang
This commit is contained in:
parent
4605870788
commit
211a7f85b5
|
@ -369,7 +369,8 @@ void ModeFlowHold::update_height_estimate(void)
|
|||
|
||||
// get delta velocity in body frame
|
||||
Vector3f delta_vel;
|
||||
if (!copter.ins.get_delta_velocity(delta_vel)) {
|
||||
float delta_vel_dt;
|
||||
if (!copter.ins.get_delta_velocity(delta_vel, delta_vel_dt)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -275,15 +275,13 @@ void ModeSystemId::run()
|
|||
// log system id and attitude
|
||||
void ModeSystemId::log_data() const
|
||||
{
|
||||
uint8_t index = copter.ahrs.get_primary_gyro_index();
|
||||
Vector3f delta_angle;
|
||||
copter.ins.get_delta_angle(index, delta_angle);
|
||||
float delta_angle_dt = copter.ins.get_delta_angle_dt(index);
|
||||
float delta_angle_dt;
|
||||
copter.ins.get_delta_angle(delta_angle, delta_angle_dt);
|
||||
|
||||
index = copter.ahrs.get_primary_accel_index();
|
||||
Vector3f delta_velocity;
|
||||
copter.ins.get_delta_velocity(index, delta_velocity);
|
||||
float delta_velocity_dt = copter.ins.get_delta_velocity_dt(index);
|
||||
float delta_velocity_dt;
|
||||
copter.ins.get_delta_velocity(delta_velocity, delta_velocity_dt);
|
||||
|
||||
if (is_positive(delta_angle_dt) && is_positive(delta_velocity_dt)) {
|
||||
copter.Log_Write_SysID_Data(waveform_time, waveform_sample, waveform_freq_rads / (2 * M_PI), degrees(delta_angle.x / delta_angle_dt), degrees(delta_angle.y / delta_angle_dt), degrees(delta_angle.z / delta_angle_dt), delta_velocity.x / delta_velocity_dt, delta_velocity.y / delta_velocity_dt, delta_velocity.z / delta_velocity_dt);
|
||||
|
|
Loading…
Reference in New Issue