Skip to content

Commit

Permalink
Merge branch 'master' into drivers/SPA06_baro
Browse files Browse the repository at this point in the history
  • Loading branch information
radiolinkW authored Aug 29, 2024
2 parents 1aeb373 + 15d6e66 commit a51dfbf
Show file tree
Hide file tree
Showing 80 changed files with 872 additions and 421 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2330,7 +2330,7 @@ bool ModeAuto::resume()

bool ModeAuto::paused() const
{
return wp_nav->paused();
return (wp_nav != nullptr) && wp_nav->paused();
}

#endif
6 changes: 3 additions & 3 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,9 +204,9 @@ float Plane::stabilize_pitch_get_pitch_out()
#endif
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set
#if HAL_QUADPLANE_ENABLED
const bool quadplane_in_transition = quadplane.in_transition();
const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition();
#else
const bool quadplane_in_transition = false;
const bool quadplane_in_frwd_transition = false;
#endif

int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
Expand All @@ -219,7 +219,7 @@ float Plane::stabilize_pitch_get_pitch_out()
- throttle stick at zero thrust
- in fixed wing non auto-throttle mode
*/
if (!quadplane_in_transition &&
if (!quadplane_in_frwd_transition &&
!control_mode->is_vtol_mode() &&
!control_mode->does_auto_throttle() &&
flare_mode == FlareMode::ENABLED_PITCH_TARGET &&
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Range: 0 100
// @Increment: 1
// @User: Standard
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),

// @Param: TKOFF_OPTIONS
// @DisplayName: Takeoff options
Expand Down
6 changes: 6 additions & 0 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,9 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
case AUX_FUNC::FW_AUTOTUNE:
case AUX_FUNC::VFWD_THR_OVERRIDE:
case AUX_FUNC::PRECISION_LOITER:
#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
#endif
#if QAUTOTUNE_ENABLED
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
#endif
Expand Down Expand Up @@ -287,6 +290,9 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
case AUX_FUNC::FLAP:
case AUX_FUNC::FBWA_TAILDRAGGER:
case AUX_FUNC::AIRBRAKE:
#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
#endif
break; // input labels, nothing to do

#if HAL_QUADPLANE_ENABLED
Expand Down
10 changes: 7 additions & 3 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -813,6 +813,10 @@ bool QuadPlane::setup(void)
pilot_speed_z_max_dn.convert_centi_parameter(AP_PARAM_INT16);
pilot_accel_z.convert_centi_parameter(AP_PARAM_INT16);

// Provisionally assign the SLT thrust type.
// It will be overwritten by tailsitter or tiltorotor setups.
thrust_type = ThrustType::SLT;

tailsitter.setup();

tiltrotor.setup();
Expand Down Expand Up @@ -3970,9 +3974,9 @@ bool QuadPlane::is_vtol_land(uint16_t id) const
/*
return true if we are in a transition to fwd flight from hover
*/
bool QuadPlane::in_transition(void) const
bool QuadPlane::in_frwd_transition(void) const
{
return available() && transition->active();
return available() && transition->active_frwd();
}

/*
Expand Down Expand Up @@ -4351,7 +4355,7 @@ bool SLT_Transition::allow_update_throttle_mix() const
return !(quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER));
}

bool SLT_Transition::active() const
bool SLT_Transition::active_frwd() const
{
return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER));
}
Expand Down
15 changes: 11 additions & 4 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,13 @@ class QuadPlane
void control_auto(void);
bool setup(void);

enum class ThrustType : uint8_t {
SLT=0, // Traditional quadplane, with a pusher motor and independent multicopter lift.
TAILSITTER,
TILTROTOR,
};
ThrustType get_thrust_type(void) {return thrust_type;}

void vtol_position_controller(void);
void setup_target_position(void);
void takeoff_controller(void);
Expand Down Expand Up @@ -103,10 +110,7 @@ class QuadPlane
// abort landing, only valid when in a VTOL landing descent
bool abort_landing(void);

/*
return true if we are in a transition to fwd flight from hover
*/
bool in_transition(void) const;
bool in_frwd_transition(void) const;

bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const;

Expand Down Expand Up @@ -198,6 +202,9 @@ class QuadPlane
AP_Enum<AP_Motors::motor_frame_class> frame_class;
AP_Enum<AP_Motors::motor_frame_type> frame_type;

// Types of different "quadplane" configurations.
ThrustType thrust_type;

// Initialise motors to allow passing it to tailsitter in its constructor
AP_MotorsMulticopter *motors = nullptr;
const struct AP_Param::GroupInfo *motors_var_info;
Expand Down
18 changes: 15 additions & 3 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
slewrate = g.takeoff_throttle_slewrate;
}
#if HAL_QUADPLANE_ENABLED
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_transition()) {
if (g.takeoff_throttle_slewrate != 0 && quadplane.in_frwd_transition()) {
slewrate = g.takeoff_throttle_slewrate;
}
#endif
Expand Down Expand Up @@ -555,10 +555,22 @@ float Plane::apply_throttle_limits(float throttle_in)

// Handle throttle limits for transition conditions.
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_transition()) {
if (quadplane.in_frwd_transition()) {
if (aparm.takeoff_throttle_max != 0) {
max_throttle = aparm.takeoff_throttle_max.get();
}

// Apply minimum throttle limits only for SLT thrust types.
// The other types don't support it well.
if (quadplane.get_thrust_type() == QuadPlane::ThrustType::SLT
&& control_mode->does_auto_throttle()
) {
if (aparm.takeoff_throttle_min.get() != 0) {
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
} else {
min_throttle = MAX(min_throttle, aparm.throttle_cruise.get());
}
}
}
#endif

Expand Down Expand Up @@ -793,7 +805,7 @@ void Plane::servos_twin_engine_mix(void)
void Plane::force_flare(void)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts
if (quadplane.in_frwd_transition() && plane.arming.is_armed()) { //allows for ground checking of flare tilts
return;
}
if (control_mode->is_vtol_mode()) {
Expand Down
5 changes: 5 additions & 0 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,11 @@ void Plane::init_ardupilot()
#if AC_PRECLAND_ENABLED
g2.precland.init(scheduler.get_loop_rate_hz());
#endif

#if AP_ICENGINE_ENABLED
g2.ice_control.init();
#endif

}

#if AP_FENCE_ENABLED
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,8 @@ void Tailsitter::setup()
return;
}

quadplane.thrust_type = QuadPlane::ThrustType::TAILSITTER;

// Set tailsitter transition rate to match old calculation
if (!transition_rate_fw.configured()) {
transition_rate_fw.set_and_save(transition_angle_fw / (quadplane.transition_time_ms/2000.0f));
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/tailsitter.h
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ friend class Tailsitter;

uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }

bool active() const override { return transition_state != TRANSITION_DONE; }
bool active_frwd() const override { return transition_state == TRANSITION_ANGLE_WAIT_FW; }

bool show_vtol_view() const override;

Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,8 @@ void Tiltrotor::setup()
return;
}

quadplane.thrust_type = QuadPlane::ThrustType::TILTROTOR;

_is_vectored = tilt_mask != 0 && type == TILT_TYPE_VECTORED_YAW;

// true if a fixed forward motor is configured, either throttle, throttle left or throttle right.
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/transition.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class Transition

virtual uint8_t get_log_transition_state() const = 0;

virtual bool active() const = 0;
virtual bool active_frwd() const = 0;

virtual bool show_vtol_view() const = 0;

Expand Down Expand Up @@ -85,7 +85,7 @@ class SLT_Transition : public Transition

uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }

bool active() const override;
bool active_frwd() const override;

bool show_vtol_view() const override;

Expand Down
6 changes: 6 additions & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -321,6 +321,8 @@ AP_HW_MountainEagleH743 1444
AP_HW_StellarF4 1500
AP_HW_GEPRCF745BTHD 1501

AP_HW_HGLRCF405V4 1524

AP_HW_MFT-SEMA100 2000

AP_HW_SakuraRC-H743 2714
Expand Down Expand Up @@ -374,6 +376,10 @@ AP_HW_ZeroOne_X6 5600
AP_HW_ZeroOne_PMU 5601
AP_HW_ZeroOne_GNSS 5602

#IDs 5700-5710 reserved for DroneBuild
AP_HW_DroneBuild_G1 5700
AP_HW_DroneBuild_G2 5701

# IDs 6000-6099 reserved for SpektreWorks

# IDs 6600-6699 reserved for Eagle Eye Drones
Expand Down
10 changes: 7 additions & 3 deletions Tools/AP_Bootloader/network.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -484,10 +484,14 @@ void BL_Network::handle_request(SocketAPM *sock)
sock->send(header, strlen(header));

if (strncmp(headers, "POST / ", 7) == 0) {
const char *clen = "\r\nContent-Length:";
const char *p = strstr(headers, clen);
const char *clen1 = "\r\nContent-Length:";
const char *clen2 = "\r\ncontent-length:";
const char *p = strstr(headers, clen1);
if (p == nullptr) {
p = strstr(headers, clen2);
}
if (p != nullptr) {
p += strlen(clen);
p += strlen(clen1);
const uint32_t content_length = atoi(p);
handle_post(sock, content_length);
delete headers;
Expand Down
37 changes: 36 additions & 1 deletion Tools/ardupilotwaf/ardupilotwaf.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
from waflib.Scripting import run_command
from waflib.TaskGen import before_method, after_method, feature
import os.path, os
from pathlib import Path
from collections import OrderedDict
import subprocess

Expand Down Expand Up @@ -261,6 +262,30 @@ def ap_common_vehicle_libraries(bld):

_grouped_programs = {}


class upload_fw_blueos(Task.Task):
def run(self):
# this is rarely used, so we import requests here to avoid the overhead
import requests
binary_path = self.inputs[0].abspath()
# check if .apj file exists for chibios builds
if Path(binary_path + ".apj").exists():
binary_path = binary_path + ".apj"
bld = self.generator.bld
board = bld.bldnode.name.capitalize()
print(f"Uploading {binary_path} to BlueOS at {bld.options.upload_blueos} for board {board}")
url = f'{bld.options.upload_blueos}/ardupilot-manager/v1.0/install_firmware_from_file?board_name={board}'
files = {
'binary': open(binary_path, 'rb')
}
response = requests.post(url, files=files, verify=False)
if response.status_code != 200:
raise Errors.WafError(f"Failed to upload firmware to BlueOS: {response.status_code}: {response.text}")
print("Upload complete")

def keyword(self):
return "Uploading to BlueOS"

class check_elf_symbols(Task.Task):
color='CYAN'
always_run = True
Expand Down Expand Up @@ -309,7 +334,10 @@ def post_link(self):

check_elf_task = self.create_task('check_elf_symbols', src=link_output)
check_elf_task.set_run_after(self.link_task)

if self.bld.options.upload_blueos and self.env["BOARD_CLASS"] == "LINUX":
_upload_task = self.create_task('upload_fw_blueos', src=link_output)
_upload_task.set_run_after(self.link_task)

@conf
def ap_program(bld,
program_groups='bin',
Expand Down Expand Up @@ -641,6 +669,13 @@ def options(opt):
help='''Specify the port to be used with the --upload option. For example a port of /dev/ttyS10 indicates that serial port 10 shuld be used.
''')

g.add_option('--upload-blueos',
action='store',
dest='upload_blueos',
default=None,
help='''Automatically upload to a BlueOS device. The argument is the url for the device. http://blueos.local for example.
''')

g.add_option('--upload-force',
action='store_true',
help='''Override board type check and continue loading. Same as using uploader.py --force.
Expand Down
4 changes: 4 additions & 0 deletions Tools/ardupilotwaf/chibios.py
Original file line number Diff line number Diff line change
Expand Up @@ -452,6 +452,10 @@ def chibios_firmware(self):
_upload_task = self.create_task('upload_fw', src=apj_target)
_upload_task.set_run_after(generate_apj_task)

if self.bld.options.upload_blueos:
_upload_task = self.create_task('upload_fw_blueos', src=link_output)
_upload_task.set_run_after(generate_apj_task)

def setup_canmgr_build(cfg):
'''enable CANManager build. By doing this here we can auto-enable CAN in
the build based on the presence of CAN pins in hwdef.dat except for AP_Periph builds'''
Expand Down
Loading

0 comments on commit a51dfbf

Please sign in to comment.