mirror of https://github.com/ArduPilot/ardupilot
Copter: Change from division to multiplication
This commit is contained in:
parent
7d23d37630
commit
08a1ad3c39
|
@ -35,7 +35,7 @@ void Copter::Log_Write_Control_Tuning()
|
|||
float des_alt_m = 0.0f;
|
||||
int16_t target_climb_rate_cms = 0;
|
||||
if (!flightmode->has_manual_throttle()) {
|
||||
des_alt_m = pos_control->get_pos_target_z_cm() / 100.0f;
|
||||
des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f;
|
||||
target_climb_rate_cms = pos_control->get_vel_target_z_cms();
|
||||
}
|
||||
|
||||
|
|
|
@ -147,7 +147,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
|||
|
||||
// pass through throttle to motors
|
||||
SRV_Channels::cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||
SRV_Channels::push();
|
||||
|
||||
// read some compass values
|
||||
|
@ -157,7 +157,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
|||
battery.read();
|
||||
|
||||
// calculate scaling for throttle
|
||||
throttle_pct = (float)channel_throttle->get_control_in() / 1000.0f;
|
||||
throttle_pct = (float)channel_throttle->get_control_in() * 0.001f;
|
||||
throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
|
||||
|
||||
// record maximum throttle
|
||||
|
|
|
@ -96,7 +96,7 @@ void Copter::esc_calibration_passthrough()
|
|||
|
||||
// pass through to motors
|
||||
SRV_Channels::cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f);
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||
SRV_Channels::push();
|
||||
}
|
||||
#endif // FRAME_CONFIG != HELI_FRAME
|
||||
|
|
|
@ -713,7 +713,7 @@ void Mode::land_run_horizontal_control()
|
|||
// interpolate for 1m above that
|
||||
const float attitude_limit_cd = linear_interpolate(700, copter.aparm.angle_max, get_alt_above_ground_cm(),
|
||||
g2.wp_navalt_min*100U, (g2.wp_navalt_min+1)*100U);
|
||||
const float thrust_vector_max = sinf(radians(attitude_limit_cd / 100.0f)) * GRAVITY_MSS * 100.0f;
|
||||
const float thrust_vector_max = sinf(radians(attitude_limit_cd * 0.01f)) * GRAVITY_MSS * 100.0f;
|
||||
const float thrust_vector_mag = thrust_vector.xy().length();
|
||||
if (thrust_vector_mag > thrust_vector_max) {
|
||||
float ratio = thrust_vector_max / thrust_vector_mag;
|
||||
|
|
|
@ -179,7 +179,7 @@ void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stick_input)
|
|||
for (uint8_t i=0; i<2; i++) {
|
||||
float &velocity = sensor_flow[i];
|
||||
float abs_vel_cms = fabsf(velocity)*100;
|
||||
const float brake_gain = (15.0f * brake_rate_dps.get() + 95.0f) / 100.0f;
|
||||
const float brake_gain = (15.0f * brake_rate_dps.get() + 95.0f) * 0.01f;
|
||||
float lean_angle_cd = brake_gain * abs_vel_cms * (1.0f+500.0f/(abs_vel_cms+60.0f));
|
||||
if (velocity < 0) {
|
||||
lean_angle_cd = -lean_angle_cd;
|
||||
|
|
|
@ -41,7 +41,7 @@ bool ModePosHold::init(bool ignore_checks)
|
|||
pilot_pitch = 0.0f;
|
||||
|
||||
// compute brake_gain
|
||||
brake.gain = (15.0f * (float)g.poshold_brake_rate + 95.0f) / 100.0f;
|
||||
brake.gain = (15.0f * (float)g.poshold_brake_rate + 95.0f) * 0.01f;
|
||||
|
||||
if (copter.ap.land_complete) {
|
||||
// if landed begin in loiter mode
|
||||
|
|
|
@ -85,7 +85,7 @@ void ModeTurtle::change_motor_direction(bool reverse)
|
|||
|
||||
void ModeTurtle::run()
|
||||
{
|
||||
const float flip_power_factor = 1.0f - CRASH_FLIP_EXPO / 100.0f;
|
||||
const float flip_power_factor = 1.0f - CRASH_FLIP_EXPO * 0.01f;
|
||||
const bool norc = copter.failsafe.radio || !copter.ap.rc_receiver_present;
|
||||
const float stick_deflection_pitch = norc ? 0.0f : channel_pitch->norm_input_dz();
|
||||
const float stick_deflection_roll = norc ? 0.0f : channel_roll->norm_input_dz();
|
||||
|
|
Loading…
Reference in New Issue