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

Minor airframe spacing and float literal, cast cleanup #24094

Merged
merged 3 commits into from
Dec 12, 2024
Merged
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
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@

. ${R}etc/init.d/rc.fw_defaults


param set UAVCAN_ENABLE 0

param set-default CA_AIRFRAME 1
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@

. ${R}etc/init.d/rc.mc_defaults


param set-default MAV_TYPE 14

param set-default CA_ROTOR_COUNT 8
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/16001_helicopter
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@

. ${R}etc/init.d/rc.heli_defaults


# Disable PID gains for initial setup. These should be enabled after setting the FF gain.
# P is expected to be lower than FF.
param set-default MC_ROLLRATE_P 0
Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

. ${R}etc/init.d/rc.fw_defaults


param set-default BAT1_CAPACITY 2500
param set-default BAT1_N_CELLS 3

Expand All @@ -41,7 +40,6 @@ param set-default FW_P_LIM_MAX 25
param set-default FW_P_LIM_MIN -5
param set-default FW_P_RMAX_NEG 20


param set-default CA_AIRFRAME 1

param set-default CA_ROTOR_COUNT 1
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@

. ${R}etc/init.d/rc.fw_defaults


param set-default BAT1_CAPACITY 3300
param set-default BAT1_N_CELLS 3

Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ param set-default NAV_ACC_RAD 2
param set-default RTL_DESCEND_ALT 10
param set-default RTL_RETURN_ALT 30


param set-default CA_ROTOR_COUNT 12
# Bottom motors
param set-default CA_ROTOR0_PX 0
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/4050_generic_250
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ param set-default MC_PITCHRATE_P 0.08
param set-default MC_PITCHRATE_D 0.001
param set-default MC_YAW_P 4


param set-default MC_ROLLRATE_MAX 1600
param set-default MC_PITCHRATE_MAX 1600
param set-default MC_YAWRATE_MAX 1000
Expand Down
5 changes: 0 additions & 5 deletions ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ param set-default COM_FLTMODE5 -1
param set-default COM_FLTMODE6 1
param set-default COM_RC_LOSS_T 3


# ekf2
param set-default EKF2_BARO_NOISE 2

Expand Down Expand Up @@ -79,19 +78,16 @@ param set-default EKF2_RNG_POS_Z 0.033

param set-default EKF2_TERR_NOISE 1


# Maximum allowed angle velocity in the landed state
param set-default LNDMC_ROT_MAX 40

# Maximum vertical velocity allowed in the landed state
param set-default LNDMC_Z_VEL_MAX 0.7


# filtering
param set-default IMU_DGYRO_CUTOFF 50
param set-default IMU_GYRO_CUTOFF 65


# Pitch angle & rate setting
param set-default MC_PITCHRATE_P 0.075
param set-default MC_PITCHRATE_I 0.1
Expand Down Expand Up @@ -148,7 +144,6 @@ param set-default RC_MAP_RETURN_SW 7

param set-default RC1_TRIM 1000


# optical flow
param set-default SENS_FLOW_MAXR 7.4
param set-default SENS_FLOW_MINHGT 0.15
Expand Down
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/airframes/4071_ifo
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ param set-default IMU_DGYRO_CUTOFF 90
param set-default IMU_GYRO_CUTOFF 100

# System

param set-default SENS_BOARD_ROT 10

# EKF2
Expand Down
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#
. ${R}etc/init.d/rc.mc_defaults


param set-default SYS_HAS_MAG 0
param set-default EKF2_OF_CTRL 1
param set-default EKF2_GPS_CTRL 0
Expand Down Expand Up @@ -85,6 +84,5 @@ param set-default PWM_MAIN_MAX3 255

param set-default SENS_FLOW_MINRNG 0.05


syslink start
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ param set-default RD_YAW_I 0.1
param set-default RD_YAW_RATE_P 0.1
param set-default RD_YAW_RATE_I 0.01


# Pure pursuit parameters
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@

. ${R}etc/init.d/rc.rover_defaults


param set-default BAT1_N_CELLS 2

param set-default EKF2_ANGERR_INIT 0.01
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

. ${R}etc/init.d/rc.uuv_defaults


param set-default MAV_1_CONFIG 102

param set-default BAT1_A_PER_V 37.8798
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/distance_sensor/ll40ls_pwm/LidarLitePWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ LidarLitePWM::measure()
return PX4_ERROR;
}

const float current_distance = float(_pwm.pulse_width) * 1e-3f; /* 10 usec = 1 cm distance for LIDAR-Lite */
const float current_distance = static_cast<float>(_pwm.pulse_width) * 1e-3f; // 1us = 1mm distance for LIDAR-Lite

/* Due to a bug in older versions of the LidarLite firmware, we have to reset sensor on (distance == 0) */
if (current_distance <= 0.0f) {
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/rpm/pcf8583/PCF8583.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,8 +195,8 @@ void PCF8583::RunImpl()
}

// Calculate RPM and accuracy estimation
float indicated_rpm = (((float)diffCount / _param_pcf8583_magnet.get()) / ((float)diffTime / 1000000.f)) * 60.f;
float estimated_accurancy = 1 / (float)_param_pcf8583_magnet.get() / ((float)diffTime / 1000000) * 60.f;
float indicated_rpm = (((float)diffCount / _param_pcf8583_magnet.get()) / ((float)diffTime / 1e6f)) * 60.f;
float estimated_accurancy = 1 / (float)_param_pcf8583_magnet.get() / ((float)diffTime / 1e6f) * 60.f;

// publish data to uorb
rpm_s msg{};
Expand Down
Loading