Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
jstc4ll authored Nov 20, 2024
2 parents 97e3a97 + ec1dc7c commit 1bb43c3
Show file tree
Hide file tree
Showing 130 changed files with 1,625 additions and 1,232 deletions.
2 changes: 1 addition & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1159,7 +1159,7 @@ class Plane : public AP_Vehicle {
void servos_twin_engine_mix();
void force_flare();
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
void throttle_slew_limit();
bool suppress_throttle(void);
void update_throttle_hover();
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
Expand Down
14 changes: 8 additions & 6 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
/*****************************************
* Throttle slew limit
*****************************************/
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
void Plane::throttle_slew_limit()
{
#if HAL_QUADPLANE_ENABLED
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
Expand All @@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)

if (!do_throttle_slew) {
// only do throttle slew limiting in modes where throttle control is automatic
SRV_Channels::set_slew_rate(func, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt);
return;
}

Expand All @@ -55,7 +57,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
slewrate = g.takeoff_throttle_slewrate;
}
#endif
SRV_Channels::set_slew_rate(func, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt);
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt);
}

/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
Expand Down Expand Up @@ -793,8 +797,6 @@ void Plane::servos_twin_engine_mix(void)
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
throttle_slew_limit(SRV_Channel::k_throttleLeft);
throttle_slew_limit(SRV_Channel::k_throttleRight);
}
}

Expand Down Expand Up @@ -913,7 +915,7 @@ void Plane::set_servos(void)
airbrake_update();

// slew rate limit throttle
throttle_slew_limit(SRV_Channel::k_throttle);
throttle_slew_limit();

int8_t min_throttle = 0;
#if AP_ICENGINE_ENABLED
Expand Down
20 changes: 13 additions & 7 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,9 +289,6 @@ void Tailsitter::output(void)
return;
}

float tilt_left = 0.0f;
float tilt_right = 0.0f;

// throttle 0 to 1
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01;

Expand Down Expand Up @@ -341,6 +338,10 @@ void Tailsitter::output(void)
// set AP_MotorsMatrix throttles for forward flight
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt);

// No tilt output unless forward gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;

// in forward flight: set motor tilt servos and throttles using FW controller
if (vectored_forward_gain > 0) {
// remove scaling from surface speed scaling and apply throttle scaling
Expand Down Expand Up @@ -398,8 +399,11 @@ void Tailsitter::output(void)
}

// output tilt motors
tilt_left = 0.0f;
tilt_right = 0.0f;

// No output unless hover gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;

if (vectored_hover_gain > 0) {
const float hover_throttle = motors->get_throttle_hover();
const float output_throttle = motors->get_throttle();
Expand Down Expand Up @@ -438,8 +442,10 @@ void Tailsitter::output(void)
tailsitter_motors->set_min_throttle(0.0);
}

tilt_left = 0.0f;
tilt_right = 0.0f;
// No tilt output unless hover gain is set
float tilt_left = 0.0;
float tilt_right = 0.0;

if (vectored_hover_gain > 0) {
// thrust vectoring VTOL modes
tilt_left = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft);
Expand Down
8 changes: 7 additions & 1 deletion Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -292,7 +292,7 @@ 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_CrazyF405 1177
AP_HW_FlywooF405HD_AIOv2 1180
AP_HW_FlywooH743Pro 1181

Expand Down Expand Up @@ -407,6 +407,12 @@ AP_HW_DroneBuild_G2 5701

# IDs 6000-6099 reserved for SpektreWorks

# IDs 6100-6109 reserved for MFE
AP_HW_MFE_PDB_CAN 6100
AP_HW_MFE_POS3_CAN 6101
AP_HW_MFE_RTK_CAN 6102
AP_HW_MFE_AirSpeed_CAN 6103

# IDs 6600-6699 reserved for Eagle Eye Drones

# IDs 6900-6909 reserved for Easy Aerial
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -627,6 +627,7 @@ void AP_Periph_FW::prepare_reboot()
*/
void AP_Periph_FW::reboot(bool hold_in_bootloader)
{
prepare_reboot();
hal.scheduler->reboot(hold_in_bootloader);
}

Expand Down
3 changes: 2 additions & 1 deletion Tools/AP_Periph/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,8 @@ def build(bld):
'AP_RobotisServo',
'AP_FETtecOneWire',
'GCS_MAVLink',
'AP_Relay'
'AP_Relay',
'AP_MultiHeap',
]

bld.ap_stlib(
Expand Down
1 change: 1 addition & 0 deletions Tools/GIT_Test/GIT_Success.txt
Original file line number Diff line number Diff line change
Expand Up @@ -205,3 +205,4 @@ Naveen Kumar Kilaparthi
Amr Attia
Alessandro Martini
Eren Mert YİĞİT
Prashant Powar
1 change: 1 addition & 0 deletions Tools/ardupilotwaf/ardupilotwaf.py
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@
'AP_Beacon',
'AP_Arming',
'AP_RCMapper',
'AP_MultiHeap',
]

def get_legacy_defines(sketch_name, bld):
Expand Down
6 changes: 6 additions & 0 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -696,6 +696,12 @@ def configure_env(self, cfg, env):
cfg.define('AP_NOTIFY_LP5562_BUS', 2)
cfg.define('AP_NOTIFY_LP5562_ADDR', 0x30)

# turn on fencepoint and rallypoint protocols so they're still tested:
env.CXXFLAGS.extend([
'-DAP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED=HAL_GCS_ENABLED&&HAL_RALLY_ENABLED',
'-DAC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT=HAL_GCS_ENABLED&&AP_FENCE_ENABLED'
])

try:
env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=0')
except ValueError:
Expand Down
Loading

0 comments on commit 1bb43c3

Please sign in to comment.