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
Astik-2002 authored Feb 22, 2024
2 parents b92a373 + b19f8ed commit 8b633b4
Show file tree
Hide file tree
Showing 151 changed files with 3,768 additions and 1,885 deletions.
16 changes: 16 additions & 0 deletions .github/workflows/test_unit_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,22 @@ jobs:
PATH="/github/home/.local/bin:$PATH"
Tools/scripts/build_ci.sh
- name: Unittest extract_param_defaults
env:
PYTHONPATH: "${{ github.workspace }}/Tools/scripts:${{ github.workspace }}/modules/mavlink/pymavlink"
if: matrix.config == 'unit-tests'
run: |
Tools/autotest/unittest/extract_param_defaults_unittest.py
- name: Unittest annotate_params
env:
PYTHONPATH: "${{ github.workspace }}/Tools/scripts"
if: matrix.config == 'unit-tests'
run: |
python -m pip install --upgrade pip
pip install requests mock
Tools/autotest/unittest/annotate_params_unittest.py
- name: Archive buildlog artifacts
uses: actions/upload-artifact@v3
if: failure()
Expand Down
1 change: 1 addition & 0 deletions AntennaTracker/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,4 @@
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

#include <AP_Common/AP_FWVersionDefine.h>
#include <AP_CheckFirmware/AP_CheckFirmwareDefine.h>
3 changes: 0 additions & 3 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,9 +236,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if AP_TERRAIN_AVAILABLE
SCHED_TASK(terrain_update, 10, 100, 144),
#endif
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &copter.g2.gripper, update, 10, 75, 147),
#endif
#if AP_WINCH_ENABLED
SCHED_TASK_CLASS(AP_Winch, &copter.g2.winch, update, 50, 50, 150),
#endif
Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,10 +110,6 @@
#include <AC_WPNav/AC_WPNav_OA.h>
#include <AC_Avoidance/AP_OAPathPlanner.h>
#endif
#include <AP_Gripper/AP_Gripper_config.h>
#if AP_GRIPPER_ENABLED
# include <AP_Gripper/AP_Gripper.h>
#endif
#if AC_PRECLAND_ENABLED
# include <AC_PrecLand/AC_PrecLand.h>
# include <AC_PrecLand/AC_PrecLand_StateMachine.h>
Expand Down
23 changes: 18 additions & 5 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "Copter.h"

#include <AP_Gripper/AP_Gripper.h>

/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
Expand Down Expand Up @@ -817,11 +819,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {

// 12 was AP_Stats

#if AP_GRIPPER_ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 13, ParametersG2, AP_Gripper),
#endif
// 13 was AP_Gripper

// @Param: FRAME_CLASS
// @DisplayName: Frame Class
Expand Down Expand Up @@ -1393,6 +1391,21 @@ void Copter::load_parameters(void)
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
#endif

// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
#if AP_GRIPPER_ENABLED
{
// Find G2's Top Level Key
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
return;
}

const uint16_t old_index = 13; // Old parameter index in g2
const uint16_t old_top_element = 4045; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
AP_Param::convert_class(info.old_key, &gripper, gripper.var_info, old_index, old_top_element, false);
}
#endif

// setup AP_Param frame type flags
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_COPTER);
}
Expand Down
8 changes: 0 additions & 8 deletions ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@
#include "RC_Channel.h"
#include <AP_Proximity/AP_Proximity.h>

#include <AP_Gripper/AP_Gripper_config.h>
#if AP_GRIPPER_ENABLED
# include <AP_Gripper/AP_Gripper.h>
#endif
#if MODE_FOLLOW_ENABLED == ENABLED
# include <AP_Follow/AP_Follow.h>
#endif
Expand Down Expand Up @@ -508,10 +504,6 @@ class ParametersG2 {
AP_Button *button_ptr;
#endif

#if AP_GRIPPER_ENABLED
AP_Gripper gripper;
#endif

#if MODE_THROW_ENABLED == ENABLED
// Throw mode parameters
AP_Int8 throw_nextmode;
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ void Copter::thrust_loss_check()

#if AP_GRIPPER_ENABLED
if ((copter.g2.flight_options & uint32_t(FlightOptions::RELEASE_GRIPPER_ON_THRUST_LOSS)) != 0) {
copter.g2.gripper.release();
gripper.release();
}
#endif
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -504,7 +504,7 @@ void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){

#if AP_GRIPPER_ENABLED
if (failsafe_option(FailsafeOption::RELEASE_GRIPPER)) {
copter.g2.gripper.release();
gripper.release();
}
#endif
}
Expand Down
11 changes: 5 additions & 6 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1235,8 +1235,7 @@ void PayloadPlace::run()

#if AP_GRIPPER_ENABLED == ENABLED
// if pilot releases load manually:
if (AP::gripper() != nullptr &&
AP::gripper()->valid() && AP::gripper()->released()) {
if (AP::gripper().valid() && AP::gripper().released()) {
switch (state) {
case State::FlyToLocation:
case State::Descent_Start:
Expand Down Expand Up @@ -1334,9 +1333,9 @@ void PayloadPlace::run()
// Reinitialise vertical position controller to remove discontinuity due to touch down of payload
pos_control->init_z_controller_no_descent();
#if AP_GRIPPER_ENABLED == ENABLED
if (g2.gripper.valid()) {
if (AP::gripper().valid()) {
gcs().send_text(MAV_SEVERITY_INFO, "%s Releasing the gripper", prefix_str);
g2.gripper.release();
AP::gripper().release();
state = State::Releasing;
} else {
state = State::Delay;
Expand All @@ -1347,8 +1346,8 @@ void PayloadPlace::run()
break;

case State::Releasing:
#if AP_GRIPPER_ENABLED == ENABLED
if (g2.gripper.valid() && !g2.gripper.released()) {
#if AP_GRIPPER_ENABLED
if (AP::gripper().valid() && !AP::gripper().released()) {
break;
}
#endif
Expand Down
5 changes: 0 additions & 5 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,6 @@ static void failsafe_check_static()

void Copter::init_ardupilot()
{
// init cargo gripper
#if AP_GRIPPER_ENABLED
g2.gripper.init();
#endif

// init winch
#if AP_WINCH_ENABLED
g2.winch.init();
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,4 @@
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

#include <AP_Common/AP_FWVersionDefine.h>
#include <AP_CheckFirmware/AP_CheckFirmwareDefine.h>
3 changes: 0 additions & 3 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,9 +132,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if HAL_BUTTON_ENABLED
SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),
#endif
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
#endif
#if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landing_gear_update, 5, 50, 159),
#endif
Expand Down
23 changes: 18 additions & 5 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "Plane.h"

#include <AP_Gripper/AP_Gripper.h>

/*
* ArduPlane parameter definitions
*
Expand Down Expand Up @@ -1068,11 +1070,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("HOME_RESET_ALT", 11, ParametersG2, home_reset_threshold, 0),

#if AP_GRIPPER_ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
AP_SUBGROUPINFO(gripper, "GRIP_", 12, ParametersG2, AP_Gripper),
#endif
// 12 was AP_Gripper

// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
Expand Down Expand Up @@ -1558,6 +1556,21 @@ void Plane::load_parameters(void)
}
#endif

// PARAMETER_CONVERSION - Added: Feb-2024 for Plane-4.6
#if AP_GRIPPER_ENABLED
{
// Find G2's Top Level Key
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
return;
}

const uint16_t old_index = 12; // Old parameter index in g2
const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
AP_Param::convert_class(info.old_key, &gripper, gripper.var_info, old_index, old_top_element, false);
}
#endif

// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
#if HAL_LOGGING_ENABLED
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
Expand Down
6 changes: 0 additions & 6 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#define AP_PARAM_VEHICLE_NAME plane

#include <AP_Common/AP_Common.h>
#include <AP_Gripper/AP_Gripper.h>

// Global parameter class.
//
Expand Down Expand Up @@ -512,11 +511,6 @@ class ParametersG2 {
// home reset altitude threshold
AP_Int8 home_reset_threshold;

#if AP_GRIPPER_ENABLED
// Payload Gripper
AP_Gripper gripper;
#endif

AP_Int32 flight_options;

AP_Int8 takeoff_throttle_accel_count;
Expand Down
8 changes: 4 additions & 4 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,10 +136,10 @@ class Mode
virtual bool is_taking_off() const;

// true if throttle min/max limits should be applied
bool use_throttle_limits() const;
virtual bool use_throttle_limits() const;

// true if voltage correction should be applied to throttle
bool use_battery_compensation() const;
virtual bool use_battery_compensation() const;

protected:

Expand Down Expand Up @@ -400,10 +400,10 @@ class ModeManual : public Mode
void run() override;

// true if throttle min/max limits should be applied
bool use_throttle_limits() const { return false; }
bool use_throttle_limits() const override { return false; }

// true if voltage correction should be applied to throttle
bool use_battery_compensation() const { return false; }
bool use_battery_compensation() const override { return false; }

};

Expand Down
5 changes: 0 additions & 5 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,11 +132,6 @@ void Plane::init_ardupilot()
optflow.init(-1);
}
#endif

// init cargo gripper
#if AP_GRIPPER_ENABLED
g2.gripper.init();
#endif
}

//********************************************************************************
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,4 @@
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

#include <AP_Common/AP_FWVersionDefine.h>
#include <AP_CheckFirmware/AP_CheckFirmwareDefine.h>
3 changes: 0 additions & 3 deletions ArduSub/ArduSub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,9 +102,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66),
#endif
SCHED_TASK(terrain_update, 10, 100, 72),
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75, 75),
#endif
#if AP_STATS_ENABLED
SCHED_TASK(stats_update, 1, 200, 76),
#endif
Expand Down
40 changes: 0 additions & 40 deletions ArduSub/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,46 +123,6 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control)
return desired_rate;
}

// get_surface_tracking_climb_rate - hold vehicle at the desired distance above the ground
// returns climb rate (in cm/s) which should be passed to the position controller
float Sub::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
{
#if RANGEFINDER_ENABLED == ENABLED
static uint32_t last_call_ms = 0;
float distance_error;
float velocity_correction;
float current_alt = inertial_nav.get_position_z_up_cm();

uint32_t now = AP_HAL::millis();

// reset target altitude if this controller has just been engaged
if (now - last_call_ms > RANGEFINDER_TIMEOUT_MS) {
target_rangefinder_alt = rangefinder_state.alt_cm + current_alt_target - current_alt;
}
last_call_ms = now;

// adjust rangefinder target alt if motors have not hit their limits
if ((target_rate<0 && !motors.limit.throttle_lower) || (target_rate>0 && !motors.limit.throttle_upper)) {
target_rangefinder_alt += target_rate * dt;
}

// do not let target altitude get too far from current altitude above ground
target_rangefinder_alt = constrain_float(target_rangefinder_alt,
rangefinder_state.alt_cm - pos_control.get_pos_error_z_down_cm(),
rangefinder_state.alt_cm + pos_control.get_pos_error_z_up_cm());

// calc desired velocity correction from target rangefinder alt vs actual rangefinder alt (remove the error already passed to Altitude controller to avoid oscillations)
distance_error = (target_rangefinder_alt - rangefinder_state.alt_cm) - (current_alt_target - current_alt);
velocity_correction = distance_error * g.rangefinder_gain;
velocity_correction = constrain_float(velocity_correction, -THR_SURFACE_TRACKING_VELZ_MAX, THR_SURFACE_TRACKING_VELZ_MAX);

// return combined pilot climb rate + rate to correct rangefinder alt error
return (target_rate + velocity_correction);
#else
return (float)target_rate;
#endif
}

// rotate vector from vehicle's perspective to North-East frame
void Sub::rotate_body_frame_to_NE(float &x, float &y)
{
Expand Down
3 changes: 3 additions & 0 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,9 @@ bool GCS_MAVLINK_Sub::send_info()
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
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);

return true;
}

Expand Down
10 changes: 8 additions & 2 deletions ArduSub/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,13 @@ void Sub::Log_Write_Control_Tuning()
// get terrain altitude
float terr_alt = 0.0f;
#if AP_TERRAIN_AVAILABLE
terrain.height_above_terrain(terr_alt, true);
if (terrain.enabled()) {
terrain.height_above_terrain(terr_alt, true);
} else {
terr_alt = rangefinder_state.rangefinder_terrain_offset_cm * 0.01f;
}
#else
terr_alt = rangefinder_state.rangefinder_terrain_offset_cm * 0.01f;
#endif

struct log_Control_Tuning pkt = {
Expand All @@ -41,7 +47,7 @@ void Sub::Log_Write_Control_Tuning()
desired_alt : pos_control.get_pos_target_z_cm() / 100.0f,
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
baro_alt : barometer.get_altitude(),
desired_rangefinder_alt : (int16_t)target_rangefinder_alt,
desired_rangefinder_alt : (int16_t)mode_surftrak.get_rangefinder_target_cm(),
rangefinder_alt : rangefinder_state.alt_cm,
terr_alt : terr_alt,
target_climb_rate : (int16_t)pos_control.get_vel_target_z_cms(),
Expand Down
Loading

0 comments on commit 8b633b4

Please sign in to comment.