Skip to content

Commit

Permalink
Add CAN termination to Holybro CAN product
Browse files Browse the repository at this point in the history
  • Loading branch information
vincentpoont2 committed Dec 16, 2024
1 parent eaf20db commit 4ae7f8d
Show file tree
Hide file tree
Showing 228 changed files with 12,368 additions and 1,852 deletions.
13 changes: 1 addition & 12 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ jobs:
shell: bash
run: |
sudo apt-get update
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0 cmake
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10
update-alternatives --query python
python3 --version
Expand All @@ -194,17 +194,6 @@ jobs:
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.11 11
update-alternatives --query python
rm -rf /usr/local/bin/cmake
sudo apt-get remove --purge --auto-remove cmake
sudo apt-get update && \
sudo apt-get install -y software-properties-common lsb-release && \
sudo apt-get clean all
wget -O - https://apt.kitware.com/keys/kitware-archive-latest.asc 2>/dev/null | gpg --dearmor - | sudo tee /etc/apt/trusted.gpg.d/kitware.gpg >/dev/null
sudo apt-add-repository "deb https://apt.kitware.com/ubuntu/ $(lsb_release -cs) main"
sudo apt-get update
sudo apt-get install cmake
git submodule update --init --recursive --depth=1
./Tools/scripts/esp32_get_idf.sh
Expand Down
4 changes: 0 additions & 4 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,3 @@ ENV/
env.bak/
venv.bak/
autotest_result_*_junit.xml

# Ignore ESP-IDF SDK defines
/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig
/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig
49 changes: 48 additions & 1 deletion AntennaTracker/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,53 @@
Antenna Tracker Release Notes:
------------------------------------------------------------------
Release 4.6.0-beta 13 Nov 2024
Release 4.6.0-beta2 11 Dec 2024

Changes from 4.6.0-beta1

1) Board specfic changes

- FoxeerF405v2 supports BMP280 baro
- KakuteH7, H7-Mini, H7-Wing, F4 support SPA06 baro
- MUPilot support
- SkySakura H743 support
- TBS Lucid H7 support
- VUAV-V7pro README documentation fixed
- X-MAV AP-H743v2 CAN pin definition fixed

2) Copter specific enhancements and bug fixes

- AutoTune fix for calc of maximum angular acceleration
- Advanced Failsafe customer build server option

3) Plane related enhancements and bug fixes

- QuadPlane fix for QLand getting stuck in pilot repositioning
- QuikTune C++ conversion (allow running quiktun on F4 and f7 boards)
- Takeoff direction fixed when no yaw source
- TECS correctly handles home altitude changes

4) Bug Fixes and minor enhancements

- AIRSPEED_AUTOCAL mavlink message only sent when required and fixed for 2nd sensor
- CAN frame logging added to ease support
- CRSF reconnection after failsafe fixed
- EKF3 position and velocity resets default to user defined source
- Ethernet IP address default 192.168.144.x
- Fence autoenable fix when both RCn_OPTION=11/Fence and FENCE_AUTOENABLE = 3 (AutoEnableOnlyWhenArmed)
- Fence pre-arm check that vehicle is within polygon fence
- Fence handling of more than 256 items fixed
- FFT protection against divide-by-zero in Jain estimator
- Frsky telemetry apparent wind speed fixed
- Inertial sensors stop sensor converging if motors arm
- Inertial sensors check for changes to notch filters fixed
- Real Time Clock allowed to shift forward when disarmed
- ROS2/DDS get/set parameter service added
- Scripting gets memory handling improvements
- Scripting promote video-stream-information to applet
- Topotek gimbal driver uses GIA message to retrieve current angle
- Tramp VTX OSD power indicator fixed
------------------------------------------------------------------
Release 4.6.0-beta1 13 Nov 2024

Changes from 4.5.7

Expand Down
17 changes: 10 additions & 7 deletions ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,21 @@
* Attitude Rate controllers and timing
****************************************************************/

// update rate controllers and output to roll, pitch and yaw actuators
// called at 400hz by default
void Copter::run_rate_controller()
/*
update rate controller when run from main thread (normal operation)
*/
void Copter::run_rate_controller_main()
{
// set attitude and position controller loop time
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
motors->set_dt(last_loop_time_s);
attitude_control->set_dt(last_loop_time_s);
pos_control->set_dt(last_loop_time_s);
attitude_control->set_dt(last_loop_time_s);

// run low level rate controllers that only require IMU data
attitude_control->rate_controller_run();
if (!using_rate_thread) {
motors->set_dt(last_loop_time_s);
// only run the rate controller if we are not using the rate thread
attitude_control->rate_controller_run();
}
// reset sysid and other temporary inputs
attitude_control->rate_controller_target_reset();
}
Expand Down
42 changes: 35 additions & 7 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@
*/

#include "Copter.h"
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>

#define FORCE_VERSION_H_INCLUDE
#include "version.h"
Expand Down Expand Up @@ -113,15 +114,15 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
// update INS immediately to get current gyro data populated
FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
// run low level rate controllers that only require IMU data
FAST_TASK(run_rate_controller),
FAST_TASK(run_rate_controller_main),
#if AC_CUSTOMCONTROL_MULTI_ENABLED
FAST_TASK(run_custom_controller),
#endif
#if FRAME_CONFIG == HELI_FRAME
FAST_TASK(heli_update_autorotation),
#endif //HELI_FRAME
// send outputs to the motors library immediately
FAST_TASK(motors_output),
FAST_TASK(motors_output_main),
// run EKF state estimator (expensive)
FAST_TASK(read_AHRS),
#if FRAME_CONFIG == HELI_FRAME
Expand Down Expand Up @@ -259,6 +260,10 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
#if HAL_BUTTON_ENABLED
SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168),
#endif
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
// don't delete this, there is an equivalent (virtual) in AP_Vehicle for the non-rate loop case
SCHED_TASK(update_dynamic_notch_at_specified_rate_main, LOOP_RATE, 200, 215),
#endif
};

void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
Expand Down Expand Up @@ -618,12 +623,15 @@ void Copter::update_batt_compass(void)
// should be run at loop rate
void Copter::loop_rate_logging()
{
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
Log_Write_Attitude();
Log_Write_PIDS(); // only logs if PIDS bitmask is set
if (!using_rate_thread) {
Log_Write_Rate();
Log_Write_PIDS(); // only logs if PIDS bitmask is set
}
}
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
if (should_log(MASK_LOG_FTN_FAST)) {
if (should_log(MASK_LOG_FTN_FAST) && !using_rate_thread) {
AP::ins().write_notch_log_messages();
}
#endif
Expand All @@ -641,10 +649,15 @@ void Copter::ten_hz_logging_loop()
// log attitude controller data if we're not already logging at the higher rate
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
Log_Write_Attitude();
if (!using_rate_thread) {
Log_Write_Rate();
}
}
if (!should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) {
// log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set
Log_Write_PIDS();
if (!using_rate_thread) {
Log_Write_PIDS();
}
}
// log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop
if (!should_log(MASK_LOG_ATTITUDE_FAST)) {
Expand Down Expand Up @@ -789,11 +802,26 @@ void Copter::one_hz_loop()
AP_Notify::flags.flying = !ap.land_complete;

// slowly update the PID notches with the average loop rate
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
if (!using_rate_thread) {
attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
}
pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#if AC_CUSTOMCONTROL_MULTI_ENABLED
custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
#endif

#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
// see if we should have a separate rate thread
if (!started_rate_thread && get_fast_rate_type() != FastRateType::FAST_RATE_DISABLED) {
if (hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&Copter::rate_controller_thread, void),
"rate",
1536, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) {
started_rate_thread = true;
} else {
AP_BoardConfig::allocation_error("rate thread");
}
}
#endif
}

void Copter::init_simple_bearing()
Expand Down
39 changes: 37 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -631,6 +631,17 @@ class Copter : public AP_Vehicle {
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};

// type of fast rate attitude controller in operation
enum class FastRateType : uint8_t {
FAST_RATE_DISABLED = 0,
FAST_RATE_DYNAMIC = 1,
FAST_RATE_FIXED_ARMED = 2,
FAST_RATE_FIXED = 3,
};

FastRateType get_fast_rate_type() const { return FastRateType(g2.att_enable.get()); }

// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {
return (g2.flight_options & uint32_t(option)) != 0;
Expand Down Expand Up @@ -728,7 +739,25 @@ class Copter : public AP_Vehicle {
void set_accel_throttle_I_from_pilot_throttle();
void rotate_body_frame_to_NE(float &x, float &y);
uint16_t get_pilot_speed_dn() const;
void run_rate_controller();
void run_rate_controller_main();

// if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
struct RateControllerRates {
uint8_t fast_logging_rate;
uint8_t medium_logging_rate;
uint8_t filter_rate;
uint8_t main_loop_rate;
};

uint8_t calc_gyro_decimation(uint8_t gyro_decimation, uint16_t rate_hz);
void rate_controller_thread();
void rate_controller_filter_update();
void rate_controller_log_update();
void rate_controller_set_rates(uint8_t rate_decimation, RateControllerRates& rates, bool warn_cpu_high);
void enable_fast_rate_loop(uint8_t rate_decimation, RateControllerRates& rates);
void disable_fast_rate_loop(RateControllerRates& rates);
void update_dynamic_notch_at_specified_rate_main();
// endif AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED

#if AC_CUSTOMCONTROL_MULTI_ENABLED
void run_custom_controller() { custom_control.update(); }
Expand Down Expand Up @@ -878,6 +907,7 @@ class Copter : public AP_Vehicle {
// Log.cpp
void Log_Write_Control_Tuning();
void Log_Write_Attitude();
void Log_Write_Rate();
void Log_Write_EKF_POS();
void Log_Write_PIDS();
void Log_Write_Data(LogDataID id, int32_t value);
Expand All @@ -892,6 +922,7 @@ class Copter : public AP_Vehicle {
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
void Log_Write_Vehicle_Startup_Messages();
void Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin);
#endif // HAL_LOGGING_ENABLED

// mode.cpp
Expand Down Expand Up @@ -921,7 +952,8 @@ class Copter : public AP_Vehicle {
// motors.cpp
void arm_motors_check();
void auto_disarm_check();
void motors_output();
void motors_output(bool full_push = true);
void motors_output_main();
void lost_vehicle_check();

// navigation.cpp
Expand Down Expand Up @@ -1086,6 +1118,9 @@ class Copter : public AP_Vehicle {
Mode *mode_from_mode_num(const Mode::Number mode);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);

bool started_rate_thread;
bool using_rate_thread;

public:
void failsafe_check(); // failsafe.cpp
};
Expand Down
42 changes: 42 additions & 0 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "Copter.h"
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>

#if HAL_LOGGING_ENABLED

Expand Down Expand Up @@ -76,6 +77,10 @@ void Copter::Log_Write_Control_Tuning()
void Copter::Log_Write_Attitude()
{
attitude_control->Write_ANG();
}

void Copter::Log_Write_Rate()
{
attitude_control->Write_Rate(*pos_control);
}

Expand Down Expand Up @@ -339,6 +344,16 @@ struct PACKED log_Guided_Attitude_Target {
float climb_rate;
};

// rate thread dt stats
struct PACKED log_Rate_Thread_Dt {
LOG_PACKET_HEADER;
uint64_t time_us;
float dt;
float dtAvg;
float dtMax;
float dtMin;
};

// Write a Guided mode position target
// pos_target is lat, lon, alt OR offset from ekf origin in cm
// terrain should be 0 if pos_target.z is alt-above-ekf-origin, 1 if alt-above-terrain
Expand Down Expand Up @@ -386,6 +401,21 @@ void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, f
logger.WriteBlock(&pkt, sizeof(pkt));
}

void Copter::Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin)
{
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
const log_Rate_Thread_Dt pkt {
LOG_PACKET_HEADER_INIT(LOG_RATE_THREAD_DT_MSG),
time_us : AP_HAL::micros64(),
dt : dt,
dtAvg : dtAvg,
dtMax : dtMax,
dtMin : dtMin
};
logger.WriteBlock(&pkt, sizeof(pkt));
#endif
}

// type and unit information can be found in
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
// units and "Format characters" for field type information
Expand Down Expand Up @@ -527,6 +557,18 @@ const struct LogStructure Copter::log_structure[] = {

{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },

// @LoggerMessage: RTDT
// @Description: Attitude controller time deltas
// @Field: TimeUS: Time since system startup
// @Field: dt: current time delta
// @Field: dtAvg: current time delta average
// @Field: dtMax: Max time delta since last log output
// @Field: dtMin: Min time delta since last log output

{ LOG_RATE_THREAD_DT_MSG, sizeof(log_Rate_Thread_Dt),
"RTDT", "Qffff", "TimeUS,dt,dtAvg,dtMax,dtMin", "sssss", "F----" , true },

};

uint8_t Copter::get_num_log_structures() const
Expand Down
Loading

0 comments on commit 4ae7f8d

Please sign in to comment.