Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Global: Change division to multiplication #26855

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions AntennaTracker/tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,10 @@ void Tracker::update_bearing_and_distance()

// calculate altitude difference to vehicle using gps
if (g.alt_source == ALT_SOURCE_GPS){
nav_status.alt_difference_gps = (vehicle.location_estimate.alt - current_loc.alt) / 100.0f;
nav_status.alt_difference_gps = (vehicle.location_estimate.alt - current_loc.alt) * 0.01f;
} else {
// g.alt_source == ALT_SOURCE_GPS_VEH_ONLY
nav_status.alt_difference_gps = vehicle.relative_alt / 100.0f;
nav_status.alt_difference_gps = vehicle.relative_alt * 0.01f;
}

// calculate pitch to vehicle
Expand Down Expand Up @@ -140,7 +140,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
vehicle.location.lng = msg.lon;
vehicle.location.alt = msg.alt/10;
vehicle.relative_alt = msg.relative_alt/10;
vehicle.vel = Vector3f(msg.vx/100.0f, msg.vy/100.0f, msg.vz/100.0f);
vehicle.vel = Vector3f(msg.vx*0.01f, msg.vy*0.01f, msg.vz*0.01f);
vehicle.last_update_us = AP_HAL::micros();
vehicle.last_update_ms = AP_HAL::millis();
#if HAL_LOGGING_ENABLED
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -707,8 +707,8 @@ void RC_Channel_Copter::do_aux_function_change_force_flying(const AuxSwitchPos c
void Copter::save_trim()
{
// save roll and pitch trim
float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
float roll_trim = ToRad((float)channel_roll->get_control_in()*0.01f);
float pitch_trim = ToRad((float)channel_pitch->get_control_in()*0.01f);
ahrs.add_trim(roll_trim, pitch_trim);
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ bool GCS_MAVLINK_Sub::send_info()
send_named_float("RollPitch", sub.roll_pitch_flag);

CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("RFTarget", sub.mode_surftrak.get_rangefinder_target_cm() / 100.0f);
send_named_float("RFTarget", sub.mode_surftrak.get_rangefinder_target_cm() * 0.01f);

return true;
}
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ void Sub::Log_Write_Control_Tuning()
angle_boost : attitude_control.angle_boost(),
throttle_out : motors.get_throttle(),
throttle_hover : motors.get_throttle_hover(),
desired_alt : pos_control.get_pos_target_z_cm() / 100.0f,
desired_alt : pos_control.get_pos_target_z_cm() * 0.01f,
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
baro_alt : barometer.get_altitude(),
desired_rangefinder_alt : (int16_t)mode_surftrak.get_rangefinder_target_cm(),
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ bool Sub::handle_do_motor_test(mavlink_command_int_t command) {

if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {
throttle = constrain_float(throttle, 0.0f, 100.0f);
throttle = channel_throttle->get_radio_min() + throttle / 100.0f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
throttle = channel_throttle->get_radio_min() + throttle * 0.01f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
return motors.output_test_num(motor_number, throttle); // true if motor output is set
}

Expand Down
4 changes: 2 additions & 2 deletions ArduSub/surface_bottom_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,9 @@ void Sub::update_surface_and_bottom_detector()


if (ap.at_surface) {
set_surfaced(current_depth > g.surface_depth/100.0 - 0.05); // add a 5cm buffer so it doesn't trigger too often
set_surfaced(current_depth > g.surface_depth*0.01 - 0.05); // add a 5cm buffer so it doesn't trigger too often
} else {
set_surfaced(current_depth > g.surface_depth/100.0); // If we are above surface depth, we are surfaced
set_surfaced(current_depth > g.surface_depth*0.01); // If we are above surface depth, we are surfaced
}


Expand Down
4 changes: 2 additions & 2 deletions Blimp/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,8 +129,8 @@ bool RC_Channel_Blimp::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
void Blimp::save_trim()
{
// save roll and pitch trim
float roll_trim = ToRad((float)channel_right->get_control_in()/100.0f);
float pitch_trim = ToRad((float)channel_front->get_control_in()/100.0f);
float roll_trim = ToRad((float)channel_right->get_control_in()*0.01f);
float pitch_trim = ToRad((float)channel_front->get_control_in()*0.01f);
ahrs.add_trim(roll_trim, pitch_trim);
LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM);
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/buzzer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ void AP_Periph_FW::handle_beep_command(CanardInstance* canard_instance, CanardRx
buzzer_start_ms = AP_HAL::millis();
buzzer_len_ms = req.duration*1000;
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
float volume = constrain_float(periph.g.buzz_volume/100.0f, 0, 1);
float volume = constrain_float(periph.g.buzz_volume*0.01f, 0, 1);
#elif defined(HAL_PERIPH_ENABLE_NOTIFY)
float volume = constrain_float(periph.notify.get_buzz_volume()/100.0f, 0, 1);
float volume = constrain_float(periph.notify.get_buzz_volume()*0.01f, 0, 1);
#endif
hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000));
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Devo_Telem/AP_Devo_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(int32_t ddm)
int32_t deg = (int32_t)(ddm * 1e-7);
float mm = (ddm * 1.0e-7 - deg) * 60.0f;

mm = ((float)deg * 100.0f + mm) /100.0f;
mm = ((float)deg * 100.0f + mm) *0.01f;

if ((mm < -180.0f) || (mm > 180.0f)) {
mm = 0.0f;
Expand Down
16 changes: 8 additions & 8 deletions libraries/AP_EFI/AP_EFI_Serial_MS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,41 +101,41 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data()
offset++;
break;
case ADVANCE_MSB:
internal_state.cylinder_status.ignition_timing_deg = (float)((data << 8) + read_byte_CRC32())/10.0f;
internal_state.cylinder_status.ignition_timing_deg = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
break;
case ENGINE_BM:
break;
case BAROMETER_MSB:
internal_state.atmospheric_pressure_kpa = (float)((data << 8) + read_byte_CRC32())/10.0f;
internal_state.atmospheric_pressure_kpa = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
break;
case MAP_MSB:
internal_state.intake_manifold_pressure_kpa = (float)((data << 8) + read_byte_CRC32())/10.0f;
internal_state.intake_manifold_pressure_kpa = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
break;
case MAT_MSB:
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
internal_state.intake_manifold_temperature = degF_to_Kelvin(temp_float);
break;
case CHT_MSB:
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
internal_state.cylinder_status.cylinder_head_temperature = degF_to_Kelvin(temp_float);
break;
case TPS_MSB:
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
internal_state.throttle_position_percent = roundf(temp_float);
break;
case AFR1_MSB:
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;
offset++;
internal_state.cylinder_status.lambda_coefficient = temp_float;
break;
case DWELL_MSB:
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
temp_float = (float)((data << 8) + read_byte_CRC32())*0.1f;
internal_state.spark_dwell_time_ms = temp_float;
offset++;
break;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/CANFDIface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1156,10 +1156,10 @@ void CANIface::get_stats(ExpandingString &str)
STM32_FDCANCLK/1000000UL,
_bitrate, unsigned(timings.prescaler),
unsigned(timings.sjw), unsigned(timings.bs1),
unsigned(timings.bs2), timings.sample_point_permill/10.0f,
unsigned(timings.bs2), timings.sample_point_permill*0.1f,
_fdbitrate, unsigned(fdtimings.prescaler),
unsigned(fdtimings.sjw), unsigned(fdtimings.bs1),
unsigned(fdtimings.bs2), fdtimings.sample_point_permill/10.0f,
unsigned(fdtimings.bs2), fdtimings.sample_point_permill*0.1f,
stats.tx_requests,
stats.tx_rejected,
stats.tx_overflow,
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ESP32/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ uint16_t RCOutput::read(uint8_t chan)
pwm_out &out = pwm_group_list[chan];
double freq = mcpwm_get_frequency(out.unit_num, out.timer_num);
double dprc = mcpwm_get_duty(out.unit_num, out.timer_num, out.op);
return (1000000.0 * (dprc / 100.)) / freq;
return (1000000.0 * (dprc * 0.01)) / freq;
}

void RCOutput::read(uint16_t *period_us, uint8_t len)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_IOMCU/AP_IOMCU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ void AP_IOMCU::read_erpm()
for (uint8_t j = 0; j < 4; j++) {
const uint8_t esc_id = (i * 4 + j);
if (dshot_erpm.update_mask & 1U<<esc_id) {
update_rpm(esc_id, dshot_erpm.erpm[esc_id] * 200U / motor_poles, dshot_telem[i].error_rate[j] / 100.0);
update_rpm(esc_id, dshot_erpm.erpm[esc_id] * 200U / motor_poles, dshot_telem[i].error_rate[j] * 0.01);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ bool AP_RangeFinder_BLPing::get_reading(float &reading_m)
}
if (protocol.parse_byte(b) == PingProtocol::MessageId::DISTANCE_SIMPLE) {
averageStruct.count++;
averageStruct.sum_cm += protocol.get_distance_mm()/10.0f;
averageStruct.sum_cm += protocol.get_distance_mm()*0.1f;
}
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ bool AP_RangeFinder_LeddarVu8::get_reading(float &reading_m)
} else {
// if only out of range readings return larger of
// driver defined maximum range for the model and user defined max range + 1m
reading_m = MAX(LEDDARVU8_DIST_MAX_CM, max_distance_cm() + LEDDARVU8_OUT_OF_RANGE_ADD_CM)/100.0f;
reading_m = MAX(LEDDARVU8_DIST_MAX_CM, max_distance_cm() + LEDDARVU8_OUT_OF_RANGE_ADD_CM)*0.01f;
}
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -807,7 +807,7 @@ void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch &notch)
} else
#else // APM_BUILD_Rover
const AP_MotorsUGV *motors = AP::motors_ugv();
const float motors_throttle = motors != nullptr ? abs(motors->get_throttle() / 100.0f) : 0;
const float motors_throttle = motors != nullptr ? abs(motors->get_throttle() * 0.01f) : 0;
#endif
{
float throttle_freq = ref_freq * sqrtf(MAX(0,motors_throttle) / ref);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_VideoTX/AP_VideoTX.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ uint8_t AP_VideoTX::update_power_dbm(uint8_t power, PowerActive active)
_power_levels[VTX_MAX_POWER_LEVELS-1].dbm = power;
_power_levels[VTX_MAX_POWER_LEVELS-1].level = 255;
_power_levels[VTX_MAX_POWER_LEVELS-1].dac = 255;
_power_levels[VTX_MAX_POWER_LEVELS-1].mw = uint16_t(roundf(powf(10, power / 10.0f)));
_power_levels[VTX_MAX_POWER_LEVELS-1].mw = uint16_t(roundf(powf(10, power * 0.1f)));
_power_levels[VTX_MAX_POWER_LEVELS-1].active = active;
debug("non-standard power %ddbm -> %dmw", power, _power_levels[VTX_MAX_POWER_LEVELS-1].mw);
return VTX_MAX_POWER_LEVELS-1;
Expand Down
Loading