From 49563910041bd60ff6413f664f3ddd106f8d7a8a Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:12:33 +0900 Subject: [PATCH 01/14] Tracker: Change division to multiplication --- AntennaTracker/tracking.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index 8a1240d2ee391..ec17f7da91c4c 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -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 @@ -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 From 9e460e6c9a77fe0d4c4597d443d9498a75934544 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:13:00 +0900 Subject: [PATCH 02/14] Copter: Change division to multiplication --- ArduCopter/RC_Channel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index fdb175f80c5b8..a4f9d13a594e1 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -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"); From 8f66665796aa2bfb0f4840204f81e9c5bf28edda Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:13:51 +0900 Subject: [PATCH 03/14] Sub: Change division to multiplication --- ArduSub/GCS_Mavlink.cpp | 2 +- ArduSub/Log.cpp | 2 +- ArduSub/motors.cpp | 2 +- ArduSub/surface_bottom_detector.cpp | 4 ++-- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 0d0bad47ebd89..2bb754cdd6c1b 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -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; } diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 88642afe26e3d..51d02ea560ac7 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -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(), diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 5d45a2c00fbe2..bccb870be1ddb 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -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 } diff --git a/ArduSub/surface_bottom_detector.cpp b/ArduSub/surface_bottom_detector.cpp index ca1b58646e337..0b53d8ec539a4 100644 --- a/ArduSub/surface_bottom_detector.cpp +++ b/ArduSub/surface_bottom_detector.cpp @@ -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 } From 23c80e9a8e06b35d8ba36e80786ac10c86f36600 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:14:26 +0900 Subject: [PATCH 04/14] Blimp: Change division to multiplication --- Blimp/RC_Channel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Blimp/RC_Channel.cpp b/Blimp/RC_Channel.cpp index 1132d82330b14..b6c44f55426ad 100644 --- a/Blimp/RC_Channel.cpp +++ b/Blimp/RC_Channel.cpp @@ -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"); From d351411a0337e167212424e0795efe7006d15440 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:15:16 +0900 Subject: [PATCH 05/14] AP_Devo_Telem: Change division to multiplication --- libraries/AP_Devo_Telem/AP_Devo_Telem.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp index e0828477f39fe..4574c1fb1ef14 100644 --- a/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp +++ b/libraries/AP_Devo_Telem/AP_Devo_Telem.cpp @@ -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; From 9ceca07546a1e9336d8be3c8f3f90e86ab151a6a Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:16:01 +0900 Subject: [PATCH 06/14] AP_EFI: Change division to multiplication --- libraries/AP_EFI/AP_EFI_Serial_MS.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp index 4c87783b1d0e7..690d12493f4c9 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp @@ -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; From 0e5817e2f5fe9630f7d26813858b0f620831b89c Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:16:40 +0900 Subject: [PATCH 07/14] AP_HAL_ChibiOS: Change division to multiplication --- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index 4d258e1c46f3e..c34b890ac2263 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -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, From 6a14f19baaa96274e36586f24ced21f0e9a08631 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:17:32 +0900 Subject: [PATCH 08/14] AP_HAL_ESP32: Change division to multiplication --- libraries/AP_HAL_ESP32/RCOutput.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/RCOutput.cpp b/libraries/AP_HAL_ESP32/RCOutput.cpp index c456b3d8edad4..73c5f1d969da2 100644 --- a/libraries/AP_HAL_ESP32/RCOutput.cpp +++ b/libraries/AP_HAL_ESP32/RCOutput.cpp @@ -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) From 431097b59faaac59c4fffe84fa69e44750a5b212 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:18:07 +0900 Subject: [PATCH 09/14] AP_IOMCU: Change division to multiplication --- libraries/AP_IOMCU/AP_IOMCU.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 77617cdb02ea4..da53059625e72 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -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< Date: Sat, 20 Apr 2024 19:20:21 +0900 Subject: [PATCH 10/14] piccolo_protocol: Change division to multiplication From 8cdd8e703869f7fd255d80d4e7c72f8a4d672abc Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:21:04 +0900 Subject: [PATCH 11/14] AP_RangeFinder: Change division to multiplication --- libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp | 2 +- libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index e7776e0f95574..0c889403a0ceb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -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; } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp index 3d90877d83880..6a2f1bf169714 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp @@ -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; } From 2e0a1940a1a1663ab78c20094b503f639ee242d3 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:21:37 +0900 Subject: [PATCH 12/14] AP_Vehicle: Change division to multiplication --- libraries/AP_Vehicle/AP_Vehicle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 562ac606075a4..6e4171fc1c16c 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -807,7 +807,7 @@ void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch) } 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); From 9235ed436ea70fd63c38c8aced2757d7bdfa0ec7 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:22:03 +0900 Subject: [PATCH 13/14] AP_VideoTX: Change division to multiplication --- libraries/AP_VideoTX/AP_VideoTX.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_VideoTX/AP_VideoTX.cpp b/libraries/AP_VideoTX/AP_VideoTX.cpp index 3f50914c16da2..79f512c65e2d7 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.cpp +++ b/libraries/AP_VideoTX/AP_VideoTX.cpp @@ -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; From be67cd5248077bc38683a24ed3e2756bbd77dfa0 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 20 Apr 2024 19:25:47 +0900 Subject: [PATCH 14/14] AP_Periph: Change division to multiplication --- Tools/AP_Periph/buzzer.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/AP_Periph/buzzer.cpp b/Tools/AP_Periph/buzzer.cpp index a683f2e0b4e86..0f7270a719def 100644 --- a/Tools/AP_Periph/buzzer.cpp +++ b/Tools/AP_Periph/buzzer.cpp @@ -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)); }