Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into ardupilot-MFE_AirSpeed_CAN
Browse files Browse the repository at this point in the history
  • Loading branch information
mikefenghao authored Jan 10, 2025
2 parents 794a370 + 6efe210 commit 5df1cbb
Show file tree
Hide file tree
Showing 127 changed files with 4,291 additions and 689 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ jobs:
NAME_DASHED=${WORKFLOWNAME//+( )/_}
echo "cache-key=${NAME_DASHED}" >> $GITHUB_OUTPUT
- uses: cygwin/cygwin-install-action@master
- uses: cygwin/cygwin-install-action@v5
with:
packages: cygwin64 gcc-g++=10.2.0-1 ccache python37 python37-future python37-lxml python37-pip python37-setuptools python37-wheel git procps gettext
add-to-path: false
Expand Down
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_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -710,8 +710,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_Sub.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 @@ -127,7 +127,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_Blimp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,8 @@ bool RC_Channel_Blimp::do_aux_function(const AuxFuncTrigger &trigger)
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
3 changes: 2 additions & 1 deletion Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -291,8 +291,9 @@ AP_HW_PhenixH7_Pro 1172
AP_HW_2RAWH743 1173
AP_HW_X-MAV-AP-H743V2 1174
AP_HW_BETAFPV_F4_2-3S_20A 1175
AP_HW_MicoAir743AIOv1 1176
AP_HW_MicoAir743-AIO 1176
AP_HW_CrazyF405 1177
AP_HW_MicoAir743v2 1179
AP_HW_FlywooF405HD_AIOv2 1180
AP_HW_FlywooH743Pro 1181
AP_HW_CBU_StampH743_LC 1182
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
1 change: 1 addition & 0 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -1390,6 +1390,7 @@ def configure_env(self, cfg, env):
]

# wrap malloc to ensure memory is zeroed
# note that this also needs to be done in the CMakeLists.txt files
env.LINKFLAGS += ['-Wl,--wrap,malloc']

if cfg.options.force_32bit:
Expand Down
10 changes: 10 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -7582,6 +7582,16 @@ def ProximitySensors(self):
"OA_TYPE": 2,
})
sensors = [ # tuples of name, prx_type
('ld06', 16, {
mavutil.mavlink.MAV_SENSOR_ROTATION_NONE: 273,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_45: 256,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_90: 1130,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_135: 696,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_180: 625,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_225: 967,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_270: 760,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_315: 771,
}),
('sf45b', 8, {
mavutil.mavlink.MAV_SENSOR_ROTATION_NONE: 270,
mavutil.mavlink.MAV_SENSOR_ROTATION_YAW_45: 258,
Expand Down
4 changes: 4 additions & 0 deletions Tools/autotest/test_build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,7 @@ def define_is_whitelisted_for_feature_in_code(self, target, define):
feature_define_whitelist.add('AP_WINCH_PWM_ENABLED')
feature_define_whitelist.add(r'AP_MOTORS_FRAME_.*_ENABLED')
feature_define_whitelist.add('AP_COPTER_ADVANCED_FAILSAFE_ENABLED')
feature_define_whitelist.add('AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED')

if target.lower() != "plane":
# only on Plane:
Expand All @@ -304,6 +305,9 @@ def define_is_whitelisted_for_feature_in_code(self, target, define):
feature_define_whitelist.add('AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED')
feature_define_whitelist.add('HAL_QUADPLANE_ENABLED')
feature_define_whitelist.add('AP_BATTERY_WATT_MAX_ENABLED')
feature_define_whitelist.add('MODE_AUTOLAND_ENABLED')
feature_define_whitelist.add('AP_PLANE_GLIDER_PULLUP_ENABLED')
feature_define_whitelist.add('AP_QUICKTUNE_ENABLED')

if target.lower() not in ["plane", "copter"]:
feature_define_whitelist.add('HAL_ADSB_ENABLED')
Expand Down
3 changes: 2 additions & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -5279,11 +5279,12 @@ def mission_item_protocol_items_from_filepath(self,
):
'''returns a list of mission-item-ints from filepath'''
# self.progress("filepath: %s" % filepath)
self.progress("Loading {loaderclass.itemstype()} (%s)" % os.path.basename(filepath))
wploader = loaderclass(
target_system=target_system,
target_component=target_component
)
itemstype = mavutil.mavlink.enums["MAV_MISSION_TYPE"][wploader.mav_mission_type()]
self.progress(f"Loading {itemstype} ({os.path.basename(filepath)}")
wploader.load(filepath)
return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:502

Expand Down
Binary file added Tools/bootloaders/MicoAir743-AIO_bl.bin
Binary file not shown.
Loading

0 comments on commit 5df1cbb

Please sign in to comment.