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
xiemengjie-kay authored Jan 15, 2024
2 parents 711054b + fb1209f commit 20f24eb
Show file tree
Hide file tree
Showing 98 changed files with 1,648 additions and 220 deletions.
1 change: 1 addition & 0 deletions .github/workflows/test_chibios.yml
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,7 @@ jobs:
signing,
CubeOrange-PPP,
CubeOrange-SOHW,
Pixhawk6X-PPPGW,
]
toolchain: [
chibios,
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -916,8 +916,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
return;
}
#endif
pitch = ahrs.pitch;
roll = ahrs.roll;
pitch = ahrs.get_pitch();
roll = ahrs.get_roll();
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
}
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,9 +129,9 @@ void GCS_MAVLINK_Plane::send_attitude() const
{
const AP_AHRS &ahrs = AP::ahrs();

float r = ahrs.roll;
float p = ahrs.pitch;
float y = ahrs.yaw;
float r = ahrs.get_roll();
float p = ahrs.get_pitch();
float y = ahrs.get_yaw();

if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) {
p -= radians(plane.g.pitch_trim_cd * 0.01f);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1090,7 +1090,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));

// breakout when within 5 degrees of the opposite direction
if (fabsF(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) {
if (fabsF(wrap_PI(ahrs.get_yaw() - breakout_direction_rad)) < radians(5.0f)) {
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
vtol_approach_s.approach_stage = APPROACH_LINE;
set_next_WP(cmd.content.location);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_cruise.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void ModeCruise::navigate()

// check if we are moving in the direction of the front of the vehicle
const int32_t ground_course_cd = plane.gps.ground_course_cd();
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.yaw)) < M_PI_2;
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.get_yaw())) < M_PI_2;

if (!locked_heading &&
plane.channel_roll->get_control_in() == 0 &&
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void ModeGuided::update()

float error = 0.0f;
if (plane.guided_state.target_heading_type == GUIDED_HEADING_HEADING) {
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().yaw);
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().get_yaw());
} else {
Vector2f groundspeed = AP::ahrs().groundspeed_vector();
error = wrap_PI(plane.guided_state.target_heading - atan2f(-groundspeed.y, -groundspeed.x) + M_PI);
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ void ModeTakeoff::update()
const float dist = target_dist;
if (!takeoff_started) {
const uint16_t altitude = plane.relative_ground_altitude(false,true);
const float direction = degrees(ahrs.yaw);
const float direction = degrees(ahrs.get_yaw());
// see if we will skip takeoff as already flying
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
if (altitude >= alt) {
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2636,7 +2636,7 @@ void QuadPlane::vtol_position_controller(void)
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
target_accel_cms = diff_wp_norm * (-target_accel*100);
target_yaw_deg = degrees(diff_wp_norm.angle());
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.yaw));
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw()));
bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60);
if (overshoot && !poscontrol.overshoot) {
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
Expand Down Expand Up @@ -3046,7 +3046,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
*/
float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const
{
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.yaw) - target_bearing_deg));
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw()) - target_bearing_deg));
const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
if (yaw_difference > 20) {
// this gives a factor of 2x reduction in max speed when
Expand Down
6 changes: 3 additions & 3 deletions ArduSub/turn_counter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@ void Sub::update_turn_counter()
// Determine state
// 0: 0-90 deg, 1: 90-180 deg, 2: -180--90 deg, 3: -90--0 deg
uint8_t turn_state;
if (ahrs.yaw >= 0.0f && ahrs.yaw < radians(90)) {
if (ahrs.get_yaw() >= 0.0f && ahrs.get_yaw() < radians(90)) {
turn_state = 0;
} else if (ahrs.yaw > radians(90)) {
} else if (ahrs.get_yaw() > radians(90)) {
turn_state = 1;
} else if (ahrs.yaw < -radians(90)) {
} else if (ahrs.get_yaw() < -radians(90)) {
turn_state = 2;
} else {
turn_state = 3;
Expand Down
6 changes: 4 additions & 2 deletions Blimp/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,10 @@ bool AP_Arming_Blimp::run_pre_arm_checks(bool display_failure)
return mandatory_checks(display_failure);
}

return fence_checks(display_failure)
& parameter_checks(display_failure)
return parameter_checks(display_failure)
#if AP_FENCE_ENABLED
& fence_checks(display_failure)
#endif
& motor_checks(display_failure)
& gcs_failsafe_check(display_failure)
& alt_checks(display_failure)
Expand Down
2 changes: 1 addition & 1 deletion Rover/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ void Rover::crash_check()
}

// Crashed if pitch/roll > crash_angle
if ((g2.crash_angle != 0) && ((fabsf(ahrs.pitch) > radians(g2.crash_angle)) || (fabsf(ahrs.roll) > radians(g2.crash_angle)))) {
if ((g2.crash_angle != 0) && ((fabsf(ahrs.get_pitch()) > radians(g2.crash_angle)) || (fabsf(ahrs.get_roll()) > radians(g2.crash_angle)))) {
crashed = true;
}

Expand Down
2 changes: 1 addition & 1 deletion Rover/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,7 +290,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)

// apply object avoidance to desired speed using half vehicle's maximum deceleration
if (avoidance_enabled) {
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.yaw, target_speed, rover.G_Dt);
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt);
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
// we are a sailboat trying to avoid fence, try a tack
if (rover.control_mode != &rover.mode_acro) {
Expand Down
4 changes: 2 additions & 2 deletions Rover/mode_circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ void ModeCircle::init_target_yaw_rad()
// if no position estimate use vehicle yaw
Vector2f curr_pos_NE;
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {
target.yaw_rad = AP::ahrs().yaw;
target.yaw_rad = AP::ahrs().get_yaw();
return;
}

Expand All @@ -126,7 +126,7 @@ void ModeCircle::init_target_yaw_rad()

// if current position is exactly at the center of the circle return vehicle yaw
if (is_zero(dist_m)) {
target.yaw_rad = AP::ahrs().yaw;
target.yaw_rad = AP::ahrs().get_yaw();
} else {
target.yaw_rad = center_to_veh.angle();
}
Expand Down
8 changes: 4 additions & 4 deletions Rover/sailboat.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ float Sailboat::get_VMG() const
return speed;
}

return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.yaw)));
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw())));
}

// handle user initiated tack while in acro mode
Expand All @@ -340,15 +340,15 @@ void Sailboat::handle_tack_request_acro()
}
// set tacking heading target to the current angle relative to the true wind but on the new tack
currently_tacking = true;
tack_heading_rad = wrap_2PI(rover.ahrs.yaw + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.yaw)));
tack_heading_rad = wrap_2PI(rover.ahrs.get_yaw() + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.get_yaw())));

tack_request_ms = AP_HAL::millis();
}

// return target heading in radians when tacking (only used in acro)
float Sailboat::get_tack_heading_rad()
{
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
((AP_HAL::millis() - tack_request_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) {
clear_tack();
}
Expand Down Expand Up @@ -494,7 +494,7 @@ float Sailboat::calc_heading(float desired_heading_cd)
// if we are tacking we maintain the target heading until the tack completes or times out
if (currently_tacking) {
// check if we have reached target
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
clear_tack();
} else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) {
// tack has taken too long
Expand Down
2 changes: 2 additions & 0 deletions Tools/AP_Bootloader/AP_Bootloader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,13 +109,15 @@ int main(void)
try_boot = false;
timeout = 0;
}
#if AP_CHECK_FIRMWARE_ENABLED
const auto ok = check_good_firmware();
if (ok != check_fw_result_t::CHECK_FW_OK) {
// bad firmware CRC, don't try and boot
timeout = 0;
try_boot = false;
led_set(LED_BAD_FW);
}
#endif // AP_CHECK_FIRMWARE_ENABLED
#ifndef BOOTLOADER_DEV_LIST
else if (timeout != 0) {
// fast boot for good firmware
Expand Down
14 changes: 14 additions & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -272,6 +272,9 @@ AP_HW_VIMDRONES_MOSAIC_X5 1405
AP_HW_VIMDRONES_MOSAIC_H 1406
AP_HW_VIMDRONES_PERIPH 1407

AP_HW_PIXHAWK6X_PERIPH 1408


# IDs 5000-5099 reserved for Carbonix
# IDs 5100-5199 reserved for SYPAQ Systems
# IDs 5200-5209 reserved for Airvolute
Expand All @@ -281,6 +284,17 @@ AP_HW_AIRVOLUTE_DCS2 5200
AP_HW_AOCODA-RC-H743DUAL 5210
AP_HW_AOCODA-RC-F405V3 5211

#IDs 5301-5399 reserved for Sierra Aerospace
AP_HW_Sierra-TrueNavPro-G4 5301
AP_HW_Sierra-TrueNavIC 5302
AP_HW_Sierra-TrueNorth-G4 5303
AP_HW_Sierra-TrueSpeed-G4 5304
AP_HW_Sierra-PrecisionPoint-G4 5305
AP_HW_Sierra-AeroNex 5306
AP_HW_Sierra-TrueFlow 5307
AP_HW_Sierra-TrueNavIC-Pro 5308
AP_HW_Sierra-F1-Pro 5309

# IDs 6000-6099 reserved for SpektreWorks

# OpenDroneID enabled boards. Use 10000 + the base board ID
Expand Down
8 changes: 4 additions & 4 deletions Tools/AP_Bootloader/support.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,10 @@
// optional uprintf() code for debug
// #define BOOTLOADER_DEBUG SD1

#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 0
#endif

#if defined(BOOTLOADER_DEV_LIST)
static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };
#if HAL_USE_SERIAL == TRUE
Expand All @@ -34,10 +38,6 @@ static uint8_t last_uart;
#define BOOTLOADER_BAUDRATE 115200
#endif

#ifndef AP_BOOTLOADER_ALWAYS_ERASE
#define AP_BOOTLOADER_ALWAYS_ERASE 0
#endif

// #pragma GCC optimize("O0")

static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms)
Expand Down
8 changes: 4 additions & 4 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,16 +100,16 @@ void AP_Periph_FW::init()

can_start();

#ifdef HAL_PERIPH_ENABLE_NETWORKING
networking_periph.init();
#endif

#if HAL_GCS_ENABLED
stm32_watchdog_pat();
gcs().init();
#endif
serial_manager.init();

#ifdef HAL_PERIPH_ENABLE_NETWORKING
networking_periph.init();
#endif

#if HAL_GCS_ENABLED
gcs().setup_console();
gcs().setup_uarts();
Expand Down
4 changes: 4 additions & 0 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@
#if HAL_WITH_ESC_TELEM
#include <AP_ESC_Telem/AP_ESC_Telem.h>
#endif
#ifdef HAL_PERIPH_ENABLE_RTC
#include <AP_RTC/AP_RTC.h>
#endif
#include <AP_RCProtocol/AP_RCProtocol_config.h>
#include "rc_in.h"
#include "batt_balance.h"
Expand All @@ -40,6 +43,7 @@
#if AP_SIM_ENABLED
#include <SITL/SITL.h>
#endif
#include <AP_AHRS/AP_AHRS.h>

#ifdef HAL_PERIPH_ENABLE_RELAY
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
Expand Down
20 changes: 20 additions & 0 deletions Tools/AP_Periph/networking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,12 +137,32 @@ const AP_Param::GroupInfo Networking_Periph::var_info[] {
AP_SUBGROUPINFO(passthru[8], "PASS9_", 19, Networking_Periph, Passthru),
#endif

#if AP_NETWORKING_BACKEND_PPP
// @Param: PPP_PORT
// @DisplayName: PPP serial port
// @Description: PPP serial port
// @Range: -1 10
AP_GROUPINFO("PPP_PORT", 20, Networking_Periph, ppp_port, AP_PERIPH_NET_PPP_PORT_DEFAULT),

// @Param: PPP_BAUD
// @DisplayName: PPP serial baudrate
// @Description: PPP serial baudrate
// @CopyFieldsFrom: SERIAL1_BAUD
AP_GROUPINFO("PPP_BAUD", 21, Networking_Periph, ppp_baud, AP_PERIPH_NET_PPP_BAUD_DEFAULT),
#endif

AP_GROUPEND
};


void Networking_Periph::init(void)
{
#if AP_NETWORKING_BACKEND_PPP
if (ppp_port >= 0) {
AP::serialmanager().set_protocol_and_baud(ppp_port, AP_SerialManager::SerialProtocol_PPP, ppp_baud.get());
}
#endif

networking_lib.init();

#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0
Expand Down
16 changes: 14 additions & 2 deletions Tools/AP_Periph/networking.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,14 @@
#define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2
#endif

#ifndef AP_PERIPH_NET_PPP_PORT_DEFAULT
#define AP_PERIPH_NET_PPP_PORT_DEFAULT -1
#endif

#ifndef AP_PERIPH_NET_PPP_BAUD_DEFAULT
#define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000
#endif

class Networking_Periph {
public:
Networking_Periph() {
Expand Down Expand Up @@ -54,7 +62,11 @@ class Networking_Periph {
#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU

AP_Networking networking_lib;
};

#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE
#if AP_NETWORKING_BACKEND_PPP
AP_Int8 ppp_port;
AP_Int32 ppp_baud;
#endif
};

#endif // HAL_PERIPH_ENABLE_NETWORKING
3 changes: 1 addition & 2 deletions Tools/AP_Periph/version.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
#define FORCE_VERSION_H_INCLUDE
#include "version.h"
#include <AP_Common/AP_FWVersionDefine.h>
#undef FORCE_VERSION_H_INCLUDE
#undef FORCE_VERSION_H_INCLUDE
17 changes: 12 additions & 5 deletions Tools/AP_Periph/version.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,19 @@
#pragma once

#include <GCS_MAVLink/GCS_MAVLink.h>
#ifndef FORCE_VERSION_H_INCLUDE
#error version.h should never be included directly. You probably want to include AP_Common/AP_FWVersion.h
#endif

#include "ap_version.h"

#define THISFIRMWARE "AP_Periph V1.7.0-dev"

// defines needed due to lack of GCS includes
#define FIRMWARE_VERSION_TYPE_DEV 0
#define FIRMWARE_VERSION_TYPE_BETA 255
#define FIRMWARE_VERSION_TYPE_OFFICIAL 255


// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 1,7,0,FIRMWARE_VERSION_TYPE_DEV

Expand All @@ -12,7 +22,4 @@
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV





#include <AP_Common/AP_FWVersionDefine.h>
Loading

0 comments on commit 20f24eb

Please sign in to comment.