Compare commits

...

14 Commits

Author SHA1 Message Date
Brown.Z fe3bc4d157 rover版本号调整:4.3.1 2 years ago
Brown.Z 814de7fbc5 GPS_Backend: make_gps_time增加check_new_itow函数,修复NMEA RTC时间不对问题 2 years ago
Brown.Z c076595b69 hwdef: 增加zr-mrover板,拷贝Pixhawk4和Pixhawk6C 2 years ago
Brown.Z a2fb61e5e4 Rover:增加zr_app文件,执行1hz,10hz,50hz循环, 3 years ago
Brown.Z 1ce4cb49b1 update .gitignore 3 years ago
Brown.Z 4a8fc0500f Log.cpp: 增加记录声呐数据,“UDSR” 3 years ago
Brown.Z 6d3d55f83c AP_RangeFinder_NMEA: 增加声呐解析,,SIP 3 years ago
Brown.Z ec7d59334e AC_ZR_App: 增加电池初始电量计算 3 years ago
Brown.Z 18df2c6d2c ArduCopter:增加zr_app文件,周期循环函数,在UserCode中调用 3 years ago
Brown.Z 80e93f3f71 AC_ZR_App: 增加降落减速;ZR参数名调整 3 years ago
Brown.Z 050d98eb0e 增加proximity uavcan 3 years ago
Brown.Z 16b69e95b1 增加UAVCAN RGB LED 3 years ago
zbr3550 c96c4654d5 增加注册到期时间判断 3 years ago
zbr3550 309fb6f12b 增加AC_ZR_App,增加一些参数 3 years ago
  1. 2
      .gitignore
  2. 5
      .pydevproject
  3. 11
      .vscode/extensions.json
  4. 4
      .vscode/settings.json
  5. 28
      ArduCopter/APM_Config.h
  6. 23
      ArduCopter/AP_Arming.cpp
  7. 3
      ArduCopter/AP_Arming.h
  8. 8
      ArduCopter/Copter.h
  9. 9
      ArduCopter/GCS_Mavlink.cpp
  10. 2
      ArduCopter/Parameters.cpp
  11. 1
      ArduCopter/Parameters.h
  12. 3
      ArduCopter/UserCode.cpp
  13. 17
      ArduCopter/mode.cpp
  14. 2
      ArduCopter/mode.h
  15. 8
      ArduCopter/mode_loiter.cpp
  16. 1
      ArduCopter/wscript
  17. 31
      ArduCopter/zr_app.cpp
  18. 12
      Rover/GCS_Mavlink.cpp
  19. 2
      Rover/GCS_Mavlink.h
  20. 20
      Rover/Log.cpp
  21. 1
      Rover/Parameters.cpp
  22. 2
      Rover/Parameters.h
  23. 5
      Rover/Rover.cpp
  24. 6
      Rover/Rover.h
  25. 6
      Rover/version.h
  26. 1
      Rover/wscript
  27. 27
      Rover/zr_app.cpp
  28. 170
      Tools/Frame_params/AION_R1_Rover.param
  29. 144
      Tools/Frame_params/ArduRoller-balancebot.param
  30. 54
      Tools/Frame_params/DJI_AGRAS_MG-1_AC413.param
  31. 94
      Tools/Frame_params/HK-HydroProInception-Rover350.param
  32. 66
      Tools/Frame_params/HK-hydrotek-Rover331.param
  33. 72
      Tools/Frame_params/Holybro-S500.param
  34. 108
      Tools/Frame_params/Holybro-kospi1.param
  35. 78
      Tools/Frame_params/ThunderTiger-ToyotaHilux-Rover.param
  36. BIN
      Tools/Frame_params/XPlane/NACA_64_xxx_Airfoils_from_TR824.zip
  37. 64
      Tools/Frame_params/amovlab-p200.param
  38. 46
      Tools/Frame_params/boogie-board-boat.param
  39. 84
      Tools/Frame_params/deset-mapping-boat.param
  40. 90
      Tools/Frame_params/eLAB_EX1050_AC34.param
  41. 134
      Tools/Frame_params/eLAB_EX700_AC34.param
  42. 192
      Tools/Frame_params/eLAB_LAB470_AC35.param
  43. 90
      Tools/Frame_params/eLAB_VEK_AI_Rover.param
  44. 58
      Tools/Frame_params/hexsoon-edu450.param
  45. 58
      Tools/Frame_params/hexsoon-td650.param
  46. 146
      Tools/Frame_params/iflight-chimera7-4.2.param
  47. BIN
      Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin
  48. BIN
      Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin
  49. BIN
      Tools/IO_Firmware/iofirmware_highpolh.bin
  50. BIN
      Tools/IO_Firmware/iofirmware_lowpolh.bin
  51. 18
      Tools/Linux_HAL_Essentials/pru/rangefinderpru/HexUtil_PRU.cmd
  52. BIN
      Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprudata.bin
  53. BIN
      Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprutext.bin
  54. 15554
      Tools/LogAnalyzer/examples/mechanical_fail.log
  55. 9500
      Tools/LogAnalyzer/examples/robert_lefebvre_octo_PM.log
  56. 8394
      Tools/LogAnalyzer/examples/tradheli_brownout.log
  57. 4
      Tools/ardupilotwaf/boards.py
  58. 12
      Tools/autotest/ArduCopter_Tests/copter_terrain_mission.txt
  59. 12
      Tools/autotest/ArduRover_Tests/DepthFinder/rover1.txt
  60. 44
      Tools/autotest/Generic_Missions/CMAC-copter-navtest.txt
  61. 16
      Tools/autotest/XPlane/Soaring in Seattle.waypoints
  62. 50
      Tools/autotest/fg_plane_view.bat
  63. 52
      Tools/autotest/fg_quad_view.bat
  64. 1
      Tools/autotest/locations.txt
  65. 120
      Tools/autotest/models/Callisto.param
  66. 357
      Tools/autotest/web-firmware/Tools/FilterTool/index.html
  67. 160
      Tools/autotest/web-firmware/index.html
  68. 64
      Tools/autotest/web/index.html
  69. BIN
      Tools/bootloaders/BirdCANdy_bl.elf
  70. BIN
      Tools/bootloaders/CUAV-Nora_bl.elf
  71. BIN
      Tools/bootloaders/CUAV-X7_bl.elf
  72. BIN
      Tools/bootloaders/CUAV_GPS_bl.elf
  73. BIN
      Tools/bootloaders/CUAVv5Nano_bl.elf
  74. BIN
      Tools/bootloaders/CUAVv5_bl.elf
  75. BIN
      Tools/bootloaders/CubeBlack_bl.elf
  76. BIN
      Tools/bootloaders/CubeOrangePlus_bl.elf
  77. BIN
      Tools/bootloaders/CubeOrange_bl.elf
  78. BIN
      Tools/bootloaders/CubeYellow_bl.elf
  79. BIN
      Tools/bootloaders/Durandal_bl.elf
  80. BIN
      Tools/bootloaders/F35Lightning_bl.elf
  81. BIN
      Tools/bootloaders/F4BY_bl.elf
  82. BIN
      Tools/bootloaders/FreeflyRTK_bl.elf
  83. BIN
      Tools/bootloaders/Hitec-Airspeed_bl.elf
  84. BIN
      Tools/bootloaders/HitecMosaic_bl.elf
  85. BIN
      Tools/bootloaders/HolybroG4_GPS_bl.elf
  86. BIN
      Tools/bootloaders/HolybroGPS_bl.elf
  87. BIN
      Tools/bootloaders/KakuteF4_bl.elf
  88. BIN
      Tools/bootloaders/KakuteF7Mini_bl.elf
  89. BIN
      Tools/bootloaders/KakuteF7_bl.elf
  90. BIN
      Tools/bootloaders/KakuteH7_bl.elf
  91. BIN
      Tools/bootloaders/MambaF405US-I2C_bl.elf
  92. BIN
      Tools/bootloaders/MatekF405-STD_bl.elf
  93. BIN
      Tools/bootloaders/MatekF405-Wing_bl.elf
  94. BIN
      Tools/bootloaders/MatekF405_bl.elf
  95. BIN
      Tools/bootloaders/MatekF765-SE_bl.elf
  96. BIN
      Tools/bootloaders/MatekF765-Wing_bl.elf
  97. BIN
      Tools/bootloaders/Nucleo-G491_bl.elf
  98. BIN
      Tools/bootloaders/NucleoH743_bl.elf
  99. BIN
      Tools/bootloaders/OMNIBUSF7V2_bl.elf
  100. BIN
      Tools/bootloaders/OmnibusNanoV6_bl.elf
  101. Some files were not shown because too many files have changed in this diff Show More

2
.gitignore vendored

@ -144,3 +144,5 @@ dumpstack_*out @@ -144,3 +144,5 @@ dumpstack_*out
build.tmp.binaries/
tasklist.json
modules/esp_idf
.vscode/
bd*.sh

5
.pydevproject

@ -1,5 +0,0 @@ @@ -1,5 +0,0 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?eclipse-pydev version="1.0"?><pydev_project>
<pydev_property name="org.python.pydev.PYTHON_PROJECT_INTERPRETER">Default</pydev_property>
<pydev_property name="org.python.pydev.PYTHON_PROJECT_VERSION">python 2.7</pydev_property>
</pydev_project>

11
.vscode/extensions.json vendored

@ -1,11 +0,0 @@ @@ -1,11 +0,0 @@
{
"recommendations": [
"ms-vscode.cpptools",
"sumneko.lua",
"ms-python.python",
"ms-python.vscode-pylance",
"streetsidesoftware.code-spell-checker",
"chiehyu.vscode-astyle",
"ardupilot-org.ardupilot-devenv"
]
}

4
.vscode/settings.json vendored

@ -1,4 +0,0 @@ @@ -1,4 +0,0 @@
{
"cSpell.language": "en-GB",
"astyle.astylerc": "${workspaceFolder}/Tools/CodeStyle/astylerc"
}

28
ArduCopter/APM_Config.h

@ -13,18 +13,18 @@ @@ -13,18 +13,18 @@
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor
//#define BEACON_ENABLED DISABLED // disable beacon support
//#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
#define BEACON_ENABLED DISABLED // disable beacon support
#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support
//#define GRIPPER_ENABLED DISABLED // disable gripper support
#define GRIPPER_ENABLED DISABLED // disable gripper support
//#define RPM_ENABLED DISABLED // disable rotations per minute sensor support
//#define STATS_ENABLED DISABLED // disable statistics support
//#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#define MODE_FLIP_ENABLED DISABLED // disable flip mode support
#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
#define MODE_FLIP_ENABLED DISABLED // disable flip mode support
//#define MODE_FOLLOW_ENABLED DISABLED // disable follow mode support
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support
@ -34,8 +34,8 @@ @@ -34,8 +34,8 @@
//#define MODE_SMARTRTL_ENABLED DISABLED // disable smartrtl mode support
//#define MODE_SPORT_ENABLED DISABLED // disable sport mode support
//#define MODE_SYSTEMID_ENABLED DISABLED // disable system ID mode support
//#define MODE_THROW_ENABLED DISABLED // disable throw mode support
//#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
#define MODE_THROW_ENABLED DISABLED // disable throw mode support
#define MODE_ZIGZAG_ENABLED DISABLED // disable zigzag mode support
//#define OSD_ENABLED DISABLED // disable on-screen-display support
//#define LANDING_GEAR_ENABLED DISABLED // disable landing gear support
@ -51,11 +51,11 @@ @@ -51,11 +51,11 @@
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
//#define USERHOOK_VARIABLES "UserVariables.h"
// Put your custom code into the UserCode.cpp with function names matching those listed below and ensure the appropriate #define below is uncommented below
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
// #define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
//#define USER_PARAMS_ENABLED ENABLED // to enable user parameters

23
ArduCopter/AP_Arming.cpp

@ -550,7 +550,11 @@ bool AP_Arming_Copter::alt_checks(bool display_failure) @@ -550,7 +550,11 @@ bool AP_Arming_Copter::alt_checks(bool display_failure)
// has side-effect that logging is started
bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
{
const auto &ahrs = AP::ahrs();
if(!mandatory_deadline_checks(false)){ // 检查注册是否到期
return false;
}
// always check if inertial nav has started and is ready
if (!ahrs.healthy()) {
@ -840,3 +844,22 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che @@ -840,3 +844,22 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
return true;
}
bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
return true;
#else
uint32_t date;
if (!copter.zr_app.check_deadline(date))
{
// check_failed(true, "无法解锁,授权于 %u-%u-%u 到期!", date / 10000, (date % 10000) / 100, date % 100);
check_failed(true, "Trial time has expired at %lu-%lu-%lu", date / 10000, (date % 10000) / 100, date % 100);
// check_failed(display_failure, "Trial time has expired at %d-%d-%d !", date / 10000, (date % 10000) / 100, date % 100);
return false;
}else{
return true;
}
#endif
}

3
ArduCopter/AP_Arming.h

@ -48,9 +48,10 @@ protected: @@ -48,9 +48,10 @@ protected:
bool gcs_failsafe_check(bool display_failure);
bool winch_checks(bool display_failure) const;
bool alt_checks(bool display_failure);
void set_pre_arm_check(bool b);
bool mandatory_deadline_checks(bool display_failure); // 飞机到期时间检查
private:
// actually contains the pre-arm checks. This is wrapped so that

8
ArduCopter/Copter.h

@ -70,6 +70,8 @@ @@ -70,6 +70,8 @@
#include <AP_ADSB/AP_ADSB.h> // ADS-B RF based collision avoidance module library
#include <AP_Proximity/AP_Proximity.h> // ArduPilot proximity sensor library
#include <AC_ZR_APP/AC_ZR_App.h>
// Configuration
#include "defines.h"
#include "config.h"
@ -1000,8 +1002,14 @@ private: @@ -1000,8 +1002,14 @@ private:
Mode *mode_from_mode_num(const Mode::Number mode);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
AC_ZR_App zr_app;
public:
void failsafe_check(); // failsafe.cpp
void zr_app_50hz();
void zr_app_10hz();
void zr_app_1hz();
};
extern Copter copter;

9
ArduCopter/GCS_Mavlink.cpp

@ -607,6 +607,15 @@ void GCS_MAVLINK_Copter::send_banner() @@ -607,6 +607,15 @@ void GCS_MAVLINK_Copter::send_banner()
char frame_and_type_string[30];
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
send_text(MAV_SEVERITY_INFO, "%s", frame_and_type_string);
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
uint32_t deadline = 0;
copter.zr_app.get_deadline_params(deadline);
send_text(MAV_SEVERITY_INFO, "Date:%lu",deadline);
send_text(MAV_SEVERITY_INFO, "ID:%lu",copter.zr_app.get_zr_sysid());
#endif
}
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)

2
ArduCopter/Parameters.cpp

@ -722,6 +722,8 @@ const AP_Param::Info Copter::var_info[] = { @@ -722,6 +722,8 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: Parameters.cpp
GOBJECT(g2, "", ParametersG2),
GOBJECT(zr_app, "ZR", AC_ZR_App),
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&copter, {group_info : AP_Vehicle::var_info} },

1
ArduCopter/Parameters.h

@ -376,6 +376,7 @@ public: @@ -376,6 +376,7 @@ public:
// 254,255: reserved
k_param_vehicle = 257, // vehicle common block of parameters
k_param_zr_app = 258, // 253 - Logging Group
// the k_param_* space is 9-bits in size
// 511: reserved

3
ArduCopter/UserCode.cpp

@ -19,6 +19,7 @@ void Copter::userhook_FastLoop() @@ -19,6 +19,7 @@ void Copter::userhook_FastLoop()
void Copter::userhook_50Hz()
{
// put your 50Hz code here
zr_app_50hz();
}
#endif
@ -26,6 +27,7 @@ void Copter::userhook_50Hz() @@ -26,6 +27,7 @@ void Copter::userhook_50Hz()
void Copter::userhook_MediumLoop()
{
// put your 10Hz code here
zr_app_10hz();
}
#endif
@ -40,6 +42,7 @@ void Copter::userhook_SlowLoop() @@ -40,6 +42,7 @@ void Copter::userhook_SlowLoop()
void Copter::userhook_SuperSlowLoop()
{
// put your 1Hz code here
zr_app_1hz();
}
#endif

17
ArduCopter/mode.cpp

@ -575,8 +575,11 @@ void Mode::land_run_vertical_control(bool pause_descent) @@ -575,8 +575,11 @@ void Mode::land_run_vertical_control(bool pause_descent)
bool ignore_descent_limit = false;
if (!pause_descent) {
// @Brown, loiter land auto deceleration
int16_t land_speed_now = get_land_deceleration();
// do not ignore limits until we have slowed down for landing
ignore_descent_limit = (MAX(g2.land_alt_low,100) > get_alt_above_ground_cm()) || copter.ap.land_complete_maybe;
ignore_descent_limit = (MAX(g2.land_alt_low,2000) > get_alt_above_ground_cm()) || copter.ap.land_complete_maybe; // 最低高度100改2000,最低20m开始降速
float max_land_descent_velocity;
if (g.land_speed_high > 0) {
@ -592,7 +595,8 @@ void Mode::land_run_vertical_control(bool pause_descent) @@ -592,7 +595,8 @@ void Mode::land_run_vertical_control(bool pause_descent)
cmb_rate = sqrt_controller(MAX(g2.land_alt_low,100)-get_alt_above_ground_cm(), pos_control->get_pos_z_p().kP(), pos_control->get_max_accel_z_cmss(), G_Dt);
// Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed.
cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed));
// cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed));
cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(land_speed_now)); // 替换速度
#if PRECISION_LANDING == ENABLED
const bool navigating = pos_control->is_active_xy();
@ -1024,3 +1028,12 @@ uint16_t Mode::get_pilot_speed_dn() @@ -1024,3 +1028,12 @@ uint16_t Mode::get_pilot_speed_dn()
{
return copter.get_pilot_speed_dn();
}
/**
* @brief
* @author ZRZK
* @return uint16_t
*/
uint16_t Mode::get_land_deceleration()
{
return copter.zr_app.get_land_deceleration(get_alt_above_ground_cm(),get_pilot_speed_dn());
}

2
ArduCopter/mode.h

@ -295,6 +295,8 @@ public: @@ -295,6 +295,8 @@ public:
GCS_Copter &gcs();
void set_throttle_takeoff(void);
uint16_t get_pilot_speed_dn(void);
uint16_t get_land_deceleration();
// end pass-through functions
};

8
ArduCopter/mode_loiter.cpp

@ -87,8 +87,11 @@ void ModeLoiter::run() @@ -87,8 +87,11 @@ void ModeLoiter::run()
float target_yaw_rate = 0.0f;
float target_climb_rate = 0.0f;
// @Brown, loiter land auto deceleration
int16_t land_speed_now = get_land_deceleration();
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
// pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
pos_control->set_max_speed_accel_z(-land_speed_now, g.pilot_speed_up, g.pilot_accel_z); // 替换速度
// process pilot inputs unless we are in radio failsafe
if (!copter.failsafe.radio) {
@ -106,7 +109,8 @@ void ModeLoiter::run() @@ -106,7 +109,8 @@ void ModeLoiter::run()
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
// target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
target_climb_rate = constrain_float(target_climb_rate, -land_speed_now, g.pilot_speed_up); // 替换速度
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
loiter_nav->clear_pilot_desired_acceleration();

1
ArduCopter/wscript

@ -31,6 +31,7 @@ def build(bld): @@ -31,6 +31,7 @@ def build(bld):
'AP_OSD',
'AC_AutoTune',
'AP_KDECAN',
'AC_ZR_APP',
],
)

31
ArduCopter/zr_app.cpp

@ -0,0 +1,31 @@ @@ -0,0 +1,31 @@
#include "Copter.h"
void Copter::zr_app_1hz()
{
static bool before_fly = true;
if(motors->armed()){
if(before_fly){
before_fly = false;
}
relay.on(3); // 电子开关,保持通路
// camera.set_in_arm_mode(true);
}else{
relay.off(3);
if(before_fly){
uint8_t bat_cnt = zr_app.get_battery_capacity(1,battery.voltage());
battery.reset_remaining(0,(float)bat_cnt );
// gcs().send_text(MAV_SEVERITY_INFO, "bat:%.2f,pst%d,%.2f",battery.voltage(),bat_cnt,(float)bat_cnt);
}
}
}
void Copter::zr_app_10hz()
{
}
void Copter::zr_app_50hz(){
}

12
Rover/GCS_Mavlink.cpp

@ -1133,3 +1133,15 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const @@ -1133,3 +1133,15 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
/**
* @brief send device id
* @
* @return char*
*/
char* GCS_MAVLINK_Rover::gcs_get_sysid_id()
{
static char buf[50];
memcpy(buf,rover.zr_app.get_sysid_board_id(),50);
return buf;
}

2
Rover/GCS_Mavlink.h

@ -30,6 +30,8 @@ protected: @@ -30,6 +30,8 @@ protected:
void send_nav_controller_output() const override;
void send_pid_tuning() override;
char* gcs_get_sysid_id() override ;
private:

20
Rover/Log.cpp

@ -77,6 +77,26 @@ void Rover::Log_Write_Depth() @@ -77,6 +77,26 @@ void Rover::Log_Write_Depth()
loc.lng,
(double)(s->distance()),
temp_C);
// @LoggerMessage: UDSR
// @Description: Depth messages on boats with downwards facing range finder
// @Field: TimeUS: Time since system startup
// @Field: Inst: Instance
// @Field: Lat: Latitude
// @Field: Lng: Longitude
// @Field: Deep: Depth as detected by the sensor
// @Field: Temp: Temperature
logger.Write("UDSR", "TimeUS,Lat,Lng,Alt,Temp,Deep,GLat,GLng,GAlt",
"sDUm--DUm", "FGGB--GGB", "QLLeffLLe",
AP_HAL::micros64(),
loc.lat,
loc.lat,
loc.alt,
temp_C,
(s->distance()),
gps.location().lat,
gps.location().lng,
gps.location().alt);
}
// send water depth and temp to ground station
gcs().send_message(MSG_WATER_DEPTH);

1
Rover/Parameters.cpp

@ -382,6 +382,7 @@ const AP_Param::Info Rover::var_info[] = { @@ -382,6 +382,7 @@ const AP_Param::Info Rover::var_info[] = {
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
GOBJECT(osd, "OSD", AP_OSD),
#endif
GOBJECT(zr_app, "ZR", AC_ZR_App),
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp

2
Rover/Parameters.h

@ -226,6 +226,8 @@ public: @@ -226,6 +226,8 @@ public:
// 254,255: reserved
k_param_vehicle = 257, // vehicle common block of parameters
k_param_zr_app = 258, // 253 - Logging Group
};
AP_Int16 format_version;

5
Rover/Rover.cpp

@ -129,6 +129,11 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { @@ -129,6 +129,11 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#if ADVANCED_FAILSAFE == ENABLED
SCHED_TASK(afs_fs_check, 10, 200, 129),
#endif
SCHED_TASK(zr_app_50hz, 50, 200, 132),
SCHED_TASK(zr_app_10hz, 10, 200, 135),
SCHED_TASK(zr_app_1hz, 1, 200, 138),
};

6
Rover/Rover.h

@ -37,6 +37,7 @@ @@ -37,6 +37,7 @@
#include <AP_Logger/AP_Logger.h>
#include <AP_OSD/AP_OSD.h>
#include <AR_Motors/AP_MotorsUGV.h>
#include <AC_ZR_APP/AC_ZR_App.h>
#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
@ -374,6 +375,7 @@ private: @@ -374,6 +375,7 @@ private:
"_failsafe_priorities is missing the sentinel");
AC_ZR_App zr_app;
public:
void failsafe_check();
// Motor test
@ -388,6 +390,10 @@ public: @@ -388,6 +390,10 @@ public:
// Simple mode
float simple_sin_yaw;
void zr_app_50hz();
void zr_app_10hz();
void zr_app_1hz();
};
extern Rover rover;

6
Rover/version.h

@ -6,14 +6,14 @@ @@ -6,14 +6,14 @@
#include "ap_version.h"
#define THISFIRMWARE "ArduRover V4.3.0-dev"
#define THISFIRMWARE "AUSV V4.3.1"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,3,1,FIRMWARE_VERSION_TYPE_DEV
#define FW_MAJOR 4
#define FW_MINOR 3
#define FW_PATCH 0
#define FW_PATCH 1
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV
#include <AP_Common/AP_FWVersionDefine.h>

1
Rover/wscript

@ -25,6 +25,7 @@ def build(bld): @@ -25,6 +25,7 @@ def build(bld):
'AP_WindVane',
'AR_Motors',
'AP_Torqeedo',
'AC_ZR_APP',
],
)

27
Rover/zr_app.cpp

@ -0,0 +1,27 @@ @@ -0,0 +1,27 @@
#include "Rover.h"
void Rover::zr_app_1hz()
{
static bool before_fly = true;
if(arming.is_armed()){
if(before_fly){
before_fly = false;
gcs().send_text(MAV_SEVERITY_INFO,"%s",zr_app.get_sysid_board_id());
}
relay.on(3); // 电子开关,保持通路
// camera.set_in_arm_mode(true);
}else{
relay.off(3);
}
}
void Rover::zr_app_10hz()
{
}
void Rover::zr_app_50hz(){
}

170
Tools/Frame_params/AION_R1_Rover.param

@ -1,85 +1,85 @@ @@ -1,85 +1,85 @@
#NOTE: AION Robotics Params for Rover V3.2.0
ACRO_TURN_RATE,120
#most users will want manual capabilites on boot without the need for a GCS to arm
ARMING_REQUIRE,0
#MIN 4S SOLO BATTERY
ARMING_VOLT_MIN,13
ATC_ACCEL_MAX,2.0
ATC_SPEED_P,0.2
ATC_SPEED_I,0.2
ATC_SPEED_D,0.0
ATC_SPEED_FILT,10
ATC_STR_ACC_MAX,180
ATC_STR_ANG_P,2.5
ATC_STR_RAT_FF,0.2
ATC_STR_RAT_P,0.0
ATC_STR_RAT_I,0.1
ATC_STR_RAT_D,0.0
ATC_STR_RAT_FILT,20
ATC_STR_RAT_MAX,120
#default aux ch to match documentation
AUX_CH,7
#cube power brick - 4s solo battery - SMBus hardware side not yet supported
BATT_AMP_OFFSET,0
BATT_AMP_PERVOLT,0.1
BATT_CAPACITY,5200
BATT_CURR_PIN,3
BATT_LOW_TIMER,10
BATT_LOW_TYPE,0
BATT_MONITOR,4
BATT_SERIAL_NUM,-1
BATT_VOLT_MULT,13.99818
BATT_VOLT_PIN,2
BRD_PWM_COUNT,2
#default save waypoint
RC7_OPTION,1
COMPASS_OFFS_MAX,2000
#default use only first (hopefully external) compass
COMPASS_USE,1
COMPASS_USE2,0
COMPASS_USE3,0
CRUISE_SPEED,1.0
CRUISE_THROTTLE,70
EK2_YAW_M_NSE,0.7
FS_CRASH_CHECK,1
#default modes
MODE_CH,5
MODE1,0
MODE2,3
MODE3,10
MODE4,12
NAVL1_PERIOD,6
NAVL1_DAMPING,0.7
NAVL1_XTRACK_I,0.02
PIVOT_TURN_ANGLE,30
#default telem radio
SERIAL1_BAUD,57
SERIAL1_PROTOCOL,1
#default APSync
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERVO1_FUNCTION,74
SERVO1_MAX,2000
SERVO1_MIN,1000
SERVO3_FUNCTION,73
SERVO3_MAX,2000
SERVO3_MIN,1000
SPEED_TURN_GAIN,50
ATC_TURN_MAX_G,0.3
TURN_RADIUS,0.9
WENC_CPR,1120
WENC_PINA,55
WENC_PINB,54
WENC_POS_X,-0.15
WENC_POS_Y,-0.16
WENC_POS_Z,0
WENC_RADIUS,0.0775
WENC_TYPE,0
WENC2_CPR,1120
WENC2_PINA,53
WENC2_PINB,52
WENC2_POS_X,-0.15
WENC2_POS_Y,0.16
WENC2_POS_Z,0
WENC_RADIUS,0.0775
WENC2_TYPE,0
#NOTE: AION Robotics Params for Rover V3.2.0
ACRO_TURN_RATE,120
#most users will want manual capabilites on boot without the need for a GCS to arm
ARMING_REQUIRE,0
#MIN 4S SOLO BATTERY
ARMING_VOLT_MIN,13
ATC_ACCEL_MAX,2.0
ATC_SPEED_P,0.2
ATC_SPEED_I,0.2
ATC_SPEED_D,0.0
ATC_SPEED_FILT,10
ATC_STR_ACC_MAX,180
ATC_STR_ANG_P,2.5
ATC_STR_RAT_FF,0.2
ATC_STR_RAT_P,0.0
ATC_STR_RAT_I,0.1
ATC_STR_RAT_D,0.0
ATC_STR_RAT_FILT,20
ATC_STR_RAT_MAX,120
#default aux ch to match documentation
AUX_CH,7
#cube power brick - 4s solo battery - SMBus hardware side not yet supported
BATT_AMP_OFFSET,0
BATT_AMP_PERVOLT,0.1
BATT_CAPACITY,5200
BATT_CURR_PIN,3
BATT_LOW_TIMER,10
BATT_LOW_TYPE,0
BATT_MONITOR,4
BATT_SERIAL_NUM,-1
BATT_VOLT_MULT,13.99818
BATT_VOLT_PIN,2
BRD_PWM_COUNT,2
#default save waypoint
RC7_OPTION,1
COMPASS_OFFS_MAX,2000
#default use only first (hopefully external) compass
COMPASS_USE,1
COMPASS_USE2,0
COMPASS_USE3,0
CRUISE_SPEED,1.0
CRUISE_THROTTLE,70
EK2_YAW_M_NSE,0.7
FS_CRASH_CHECK,1
#default modes
MODE_CH,5
MODE1,0
MODE2,3
MODE3,10
MODE4,12
NAVL1_PERIOD,6
NAVL1_DAMPING,0.7
NAVL1_XTRACK_I,0.02
PIVOT_TURN_ANGLE,30
#default telem radio
SERIAL1_BAUD,57
SERIAL1_PROTOCOL,1
#default APSync
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERVO1_FUNCTION,74
SERVO1_MAX,2000
SERVO1_MIN,1000
SERVO3_FUNCTION,73
SERVO3_MAX,2000
SERVO3_MIN,1000
SPEED_TURN_GAIN,50
ATC_TURN_MAX_G,0.3
TURN_RADIUS,0.9
WENC_CPR,1120
WENC_PINA,55
WENC_PINB,54
WENC_POS_X,-0.15
WENC_POS_Y,-0.16
WENC_POS_Z,0
WENC_RADIUS,0.0775
WENC_TYPE,0
WENC2_CPR,1120
WENC2_PINA,53
WENC2_PINB,52
WENC2_POS_X,-0.15
WENC2_POS_Y,0.16
WENC2_POS_Z,0
WENC_RADIUS,0.0775
WENC2_TYPE,0

144
Tools/Frame_params/ArduRoller-balancebot.param

@ -1,72 +1,72 @@ @@ -1,72 +1,72 @@
#NOTE: ArduRoller balance bot parameters for Rover-4.3 and higher
ACRO_TURN_RATE,90
AHRS_ORIENTATION,29
ATC_ACCEL_MAX,5
ATC_BAL_D,0.18
ATC_BAL_FF,0
ATC_BAL_FLTD,0
ATC_BAL_FILT,0
ATC_BAL_FLTE,0
ATC_BAL_I,7
ATC_BAL_IMAX,1
ATC_BAL_P,5
ATC_BAL_SPD_FF,1.0
ATC_BRAKE,1
ATC_STR_ACC_MAX,120
BAL_PITCH_MAX,10
CRASH_ANGLE,45
CRUISE_SPEED,0.4
CRUISE_THROTTLE,50
FRAME_CLASS,3
FS_CRASH_CHECK,1
MOT_PWM_TYPE,0
MOT_SLEWRATE,0
MOT_THR_MIN,6
MOT_THST_EXPO,-0.5
RELAY_PIN,-1
RELAY_PIN2,-1
SCHED_LOOP_RATE,200
SERVO1_FUNCTION,73
SERVO1_MAX,2000
SERVO1_MIN,1000
SERVO1_REVERSED,0
SERVO1_TRIM,1500
SERVO3_FUNCTION,74
SERVO3_MAX,2000
SERVO3_MIN,1000
SERVO3_REVERSED,1
SERVO3_TRIM,1500
SERVO11_FUNCTION,-1
SERVO12_FUNCTION,-1
SERVO13_FUNCTION,-1
SERVO14_FUNCTION,-1
ATC_TURN_MAX_G,0.2
WENC_CPR,1600
WENC_PINA,55
WENC_PINB,54
WENC_POS_X,0
WENC_POS_Y,-0.1
WENC_POS_Z,0
WENC_RADIUS,0.06
WENC_TYPE,1
WENC2_CPR,1600
WENC2_PINA,53
WENC2_PINB,52
WENC2_POS_X,0
WENC2_POS_Y,0.1
WENC2_POS_Z,0
WENC2_RADIUS,0.06
WENC2_TYPE,1
WRC_RATE_D,0.2
WRC_RATE_FF,4.2
WRC_RATE_FLTD,50
WRC_RATE_I,4
WRC_RATE_IMAX,1
WRC_RATE_MAX,12
WRC_RATE_P,0
WRC2_RATE_D,0.2
WRC2_RATE_FF,4.2
WRC2_RATE_FLTD,50
WRC2_RATE_I,4
WRC2_RATE_IMAX,1
WRC2_RATE_P,0
#NOTE: ArduRoller balance bot parameters for Rover-4.3 and higher
ACRO_TURN_RATE,90
AHRS_ORIENTATION,29
ATC_ACCEL_MAX,5
ATC_BAL_D,0.18
ATC_BAL_FF,0
ATC_BAL_FLTD,0
ATC_BAL_FILT,0
ATC_BAL_FLTE,0
ATC_BAL_I,7
ATC_BAL_IMAX,1
ATC_BAL_P,5
ATC_BAL_SPD_FF,1.0
ATC_BRAKE,1
ATC_STR_ACC_MAX,120
BAL_PITCH_MAX,10
CRASH_ANGLE,45
CRUISE_SPEED,0.4
CRUISE_THROTTLE,50
FRAME_CLASS,3
FS_CRASH_CHECK,1
MOT_PWM_TYPE,0
MOT_SLEWRATE,0
MOT_THR_MIN,6
MOT_THST_EXPO,-0.5
RELAY_PIN,-1
RELAY_PIN2,-1
SCHED_LOOP_RATE,200
SERVO1_FUNCTION,73
SERVO1_MAX,2000
SERVO1_MIN,1000
SERVO1_REVERSED,0
SERVO1_TRIM,1500
SERVO3_FUNCTION,74
SERVO3_MAX,2000
SERVO3_MIN,1000
SERVO3_REVERSED,1
SERVO3_TRIM,1500
SERVO11_FUNCTION,-1
SERVO12_FUNCTION,-1
SERVO13_FUNCTION,-1
SERVO14_FUNCTION,-1
ATC_TURN_MAX_G,0.2
WENC_CPR,1600
WENC_PINA,55
WENC_PINB,54
WENC_POS_X,0
WENC_POS_Y,-0.1
WENC_POS_Z,0
WENC_RADIUS,0.06
WENC_TYPE,1
WENC2_CPR,1600
WENC2_PINA,53
WENC2_PINB,52
WENC2_POS_X,0
WENC2_POS_Y,0.1
WENC2_POS_Z,0
WENC2_RADIUS,0.06
WENC2_TYPE,1
WRC_RATE_D,0.2
WRC_RATE_FF,4.2
WRC_RATE_FLTD,50
WRC_RATE_I,4
WRC_RATE_IMAX,1
WRC_RATE_MAX,12
WRC_RATE_P,0
WRC2_RATE_D,0.2
WRC2_RATE_FF,4.2
WRC2_RATE_FLTD,50
WRC2_RATE_I,4
WRC2_RATE_IMAX,1
WRC2_RATE_P,0

54
Tools/Frame_params/DJI_AGRAS_MG-1_AC413.param

@ -1,27 +1,27 @@ @@ -1,27 +1,27 @@
#NOTE: DJI AGRAS MG-1params for ArduPilot Copter 4.1.3, Provided by Axel Weckschmied
ACRO_YAW_P,1.9
ATC_ACCEL_P_MAX,46200
ATC_ACCEL_R_MAX,46200
ATC_ACCEL_Y_MAX,17100
ATC_RAT_PIT_FLTD,11.5
ATC_RAT_PIT_FLTT,11.5
ATC_RAT_RLL_FLTD,11.5
ATC_RAT_RLL_FLTT,11.5
ATC_RAT_YAW_FLTE,2
ATC_RAT_YAW_FLTT,11.5
BATT_AMP_PERVLT,36
BATT_CAPACITY,12000
BATT_MONITOR,3
BATT_VOLT_MULT,18.1
BRD_IMU_TARGTEMP,60
BRD_PWM_COUNT,5
FRAME_CLASS,3
INS_GYRO_FILTER,23
MOT_BAT_VOLT_MAX,50.4
MOT_BAT_VOLT_MIN,39.6
MOT_SPIN_ARM,0.15
MOT_SPIN_MIN,0.2
MOT_THST_EXPO,0.75
MOT_THST_HOVER,0.1869573
PSC_ACCZ_I,0.4
PSC_ACCZ_P,0.2
#NOTE: DJI AGRAS MG-1params for ArduPilot Copter 4.1.3, Provided by Axel Weckschmied
ACRO_YAW_P,1.9
ATC_ACCEL_P_MAX,46200
ATC_ACCEL_R_MAX,46200
ATC_ACCEL_Y_MAX,17100
ATC_RAT_PIT_FLTD,11.5
ATC_RAT_PIT_FLTT,11.5
ATC_RAT_RLL_FLTD,11.5
ATC_RAT_RLL_FLTT,11.5
ATC_RAT_YAW_FLTE,2
ATC_RAT_YAW_FLTT,11.5
BATT_AMP_PERVLT,36
BATT_CAPACITY,12000
BATT_MONITOR,3
BATT_VOLT_MULT,18.1
BRD_IMU_TARGTEMP,60
BRD_PWM_COUNT,5
FRAME_CLASS,3
INS_GYRO_FILTER,23
MOT_BAT_VOLT_MAX,50.4
MOT_BAT_VOLT_MIN,39.6
MOT_SPIN_ARM,0.15
MOT_SPIN_MIN,0.2
MOT_THST_EXPO,0.75
MOT_THST_HOVER,0.1869573
PSC_ACCZ_I,0.4
PSC_ACCZ_P,0.2

94
Tools/Frame_params/HK-HydroProInception-Rover350.param

@ -1,47 +1,47 @@ @@ -1,47 +1,47 @@
ACRO_TURN_RATE 180
ARMING_RUDDER 0
ATC_ACCEL_MAX 1
ATC_SPEED_D 0
ATC_SPEED_FILT 10
ATC_SPEED_I 0.3
ATC_SPEED_IMAX 1
ATC_SPEED_P 0.4
ATC_STR_ACC_MAX 360
ATC_STR_RAT_D 0
ATC_STR_RAT_FF 1.7
ATC_STR_RAT_FILT 10
ATC_STR_RAT_I 0.5
ATC_STR_RAT_MAX 180
ATC_STR_RAT_P 0.5
BRD_SAFETYENABLE 0
COMPASS_CAL_FIT 32
COMPASS_USE 1
COMPASS_USE2 0
COMPASS_USE3 0
CRUISE_SPEED 5
CRUISE_THROTTLE 50
FRAME_CLASS 2
FRAME_TYPE 0
FS_ACTION 2
FS_CRASH_CHECK 0
FS_THR_ENABLE 1
FS_THR_VALUE 910
FS_TIMEOUT 1.5
MOT_THR_MAX 80
NTF_BUZZ_ENABLE 0
PILOT_STEER_TYPE 0
SERVO1_FUNCTION 26
SERVO1_MAX 2000
SERVO1_MIN 1000
SERVO1_REVERSED 0
SERVO1_TRIM 1500
SERVO3_FUNCTION 70
SERVO3_MAX 1900
SERVO3_MIN 1100
SERVO3_REVERSED 0
SERVO3_TRIM 1500
ATC_TURN_MAX_G 0.1
TURN_RADIUS 3
WP_OVERSHOOT 6
WP_RADIUS 2
WP_SPEED 10
ACRO_TURN_RATE 180
ARMING_RUDDER 0
ATC_ACCEL_MAX 1
ATC_SPEED_D 0
ATC_SPEED_FILT 10
ATC_SPEED_I 0.3
ATC_SPEED_IMAX 1
ATC_SPEED_P 0.4
ATC_STR_ACC_MAX 360
ATC_STR_RAT_D 0
ATC_STR_RAT_FF 1.7
ATC_STR_RAT_FILT 10
ATC_STR_RAT_I 0.5
ATC_STR_RAT_MAX 180
ATC_STR_RAT_P 0.5
BRD_SAFETYENABLE 0
COMPASS_CAL_FIT 32
COMPASS_USE 1
COMPASS_USE2 0
COMPASS_USE3 0
CRUISE_SPEED 5
CRUISE_THROTTLE 50
FRAME_CLASS 2
FRAME_TYPE 0
FS_ACTION 2
FS_CRASH_CHECK 0
FS_THR_ENABLE 1
FS_THR_VALUE 910
FS_TIMEOUT 1.5
MOT_THR_MAX 80
NTF_BUZZ_ENABLE 0
PILOT_STEER_TYPE 0
SERVO1_FUNCTION 26
SERVO1_MAX 2000
SERVO1_MIN 1000
SERVO1_REVERSED 0
SERVO1_TRIM 1500
SERVO3_FUNCTION 70
SERVO3_MAX 1900
SERVO3_MIN 1100
SERVO3_REVERSED 0
SERVO3_TRIM 1500
ATC_TURN_MAX_G 0.1
TURN_RADIUS 3
WP_OVERSHOOT 6
WP_RADIUS 2
WP_SPEED 10

66
Tools/Frame_params/HK-hydrotek-Rover331.param

@ -1,33 +1,33 @@ @@ -1,33 +1,33 @@
#NOTE: HobbyKing Hydrotek using Rover-3.3.1
ACRO_TURN_RATE,120
ATC_ACCEL_MAX,2
ATC_SPEED_I,0.2
ATC_SPEED_P,0.2
ATC_STR_ACC_MAX,360
ATC_STR_ANG_P,2
ATC_STR_RAT_FF,0.6
ATC_STR_RAT_I,0.2
ATC_STR_RAT_MAX,90
ATC_STR_RAT_P,0.2
BRD_SAFETYENABLE,0
RC7_OPTION,3
COMPASS_ORIENT,4
CRUISE_SPEED,2
CRUISE_THROTTLE,20
FRAME_CLASS,2
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
SERVO1_FUNCTION,26
SERVO1_MAX,1900
SERVO1_MIN,1100
SERVO1_REVERSED,1
SERVO1_TRIM,1500
SERVO3_FUNCTION,70
SERVO3_MAX,1900
SERVO3_MIN,1100
SERVO3_REVERSED,0
SERVO3_TRIM,1500
SPEED_TURN_GAIN,50
ATC_TURN_MAX_G,0.4
WP_SPEED,4
#NOTE: HobbyKing Hydrotek using Rover-3.3.1
ACRO_TURN_RATE,120
ATC_ACCEL_MAX,2
ATC_SPEED_I,0.2
ATC_SPEED_P,0.2
ATC_STR_ACC_MAX,360
ATC_STR_ANG_P,2
ATC_STR_RAT_FF,0.6
ATC_STR_RAT_I,0.2
ATC_STR_RAT_MAX,90
ATC_STR_RAT_P,0.2
BRD_SAFETYENABLE,0
RC7_OPTION,3
COMPASS_ORIENT,4
CRUISE_SPEED,2
CRUISE_THROTTLE,20
FRAME_CLASS,2
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
SERVO1_FUNCTION,26
SERVO1_MAX,1900
SERVO1_MIN,1100
SERVO1_REVERSED,1
SERVO1_TRIM,1500
SERVO3_FUNCTION,70
SERVO3_MAX,1900
SERVO3_MIN,1100
SERVO3_REVERSED,0
SERVO3_TRIM,1500
SPEED_TURN_GAIN,50
ATC_TURN_MAX_G,0.4
WP_SPEED,4

72
Tools/Frame_params/Holybro-S500.param

@ -1,36 +1,36 @@ @@ -1,36 +1,36 @@
#Note: Holybro S500 param for ArduPilot Copter 4.1
ACRO_YAW_P,1.5
ANGLE_MAX,3500
ATC_ACCEL_P_MAX,70000
ATC_ACCEL_R_MAX,70000
ATC_ACCEL_Y_MAX,12000
ATC_ANG_PIT_P,11
ATC_ANG_RLL_P,11
ATC_ANG_YAW_P,7.2
ATC_RAT_PIT_D,0.003
ATC_RAT_PIT_I,0.110
ATC_RAT_PIT_P,0.110
ATC_RAT_RLL_D,0.003
ATC_RAT_RLL_I,0.110
ATC_RAT_RLL_P,0.110
ATC_RAT_YAW_FLTE,1
ATC_RAT_YAW_I,0.031
ATC_RAT_YAW_P,0.31
BATT_AMP_PERVLT,39.877
BATT_CURR_PIN,1
BATT_LOW_VOLT,14
BATT_MONITOR,4
BATT_VOLT_MULT,18.182
BATT_VOLT_PIN,0
BRD_SAFETYENABLE,0
EK3_DRAG_BCOEF_X,80
EK3_DRAG_BCOEF_Y,54
EK3_DRAG_MCOEF,0.11
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,16.8
MOT_BAT_VOLT_MIN,13.2
MOT_SPIN_ARM,0.07
MOT_SPIN_MIN,0.09
MOT_THST_HOVER,0.25
#Note: Holybro S500 param for ArduPilot Copter 4.1
ACRO_YAW_P,1.5
ANGLE_MAX,3500
ATC_ACCEL_P_MAX,70000
ATC_ACCEL_R_MAX,70000
ATC_ACCEL_Y_MAX,12000
ATC_ANG_PIT_P,11
ATC_ANG_RLL_P,11
ATC_ANG_YAW_P,7.2
ATC_RAT_PIT_D,0.003
ATC_RAT_PIT_I,0.110
ATC_RAT_PIT_P,0.110
ATC_RAT_RLL_D,0.003
ATC_RAT_RLL_I,0.110
ATC_RAT_RLL_P,0.110
ATC_RAT_YAW_FLTE,1
ATC_RAT_YAW_I,0.031
ATC_RAT_YAW_P,0.31
BATT_AMP_PERVLT,39.877
BATT_CURR_PIN,1
BATT_LOW_VOLT,14
BATT_MONITOR,4
BATT_VOLT_MULT,18.182
BATT_VOLT_PIN,0
BRD_SAFETYENABLE,0
EK3_DRAG_BCOEF_X,80
EK3_DRAG_BCOEF_Y,54
EK3_DRAG_MCOEF,0.11
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,16.8
MOT_BAT_VOLT_MIN,13.2
MOT_SPIN_ARM,0.07
MOT_SPIN_MIN,0.09
MOT_THST_HOVER,0.25

108
Tools/Frame_params/Holybro-kospi1.param

@ -1,54 +1,54 @@ @@ -1,54 +1,54 @@
#NOTE: Holybro Kospi1 default params for Copter-3.6 (and higher)
ACRO_RP_P,9
ACRO_TRAINER,0
AHRS_EKF_TYPE,3
ATC_ACCEL_P_MAX,256000
ATC_ACCEL_R_MAX,364000
ATC_ACCEL_Y_MAX,89000
ATC_ANGLE_BOOST,0
ATC_ANG_PIT_P,25.0
ATC_ANG_RLL_P,25.0
ATC_ANG_YAW_P,14.1
ATC_INPUT_TC,0.05
ATC_RAT_PIT_D,0.001486
ATC_RAT_PIT_FILT,40
ATC_RAT_PIT_FLTD,40
ATC_RAT_PIT_I,0.066914
ATC_RAT_PIT_P,0.066914
ATC_RAT_RLL_D,0.001125
ATC_RAT_RLL_FILT,40
ATC_RAT_RLL_FLTD,40
ATC_RAT_RLL_I,0.054774
ATC_RAT_RLL_P,0.054774
ATC_RAT_YAW_FILT,3.491686
ATC_RAT_YAW_FLTE,3.491686
ATC_RAT_YAW_I,0.02087
ATC_RAT_YAW_P,0.208696
BATT_MONITOR,4
BRD_PWM_COUNT,8
EK2_ENABLE,0
EK3_ENABLE,1
FRAME_CLASS,1
INS_ACCEL_FILTER,10
INS_GYRO_FILTER,80
LOG_BITMASK,65534
MOT_PWM_MAX,2000
MOT_PWM_MIN,1000
MOT_PWM_TYPE,4
MOT_SPIN_MIN,0.1
MOT_THST_EXPO,0.5
MOT_THST_HOVER,0.125
PILOT_ACCEL_Z,800
PILOT_SPEED_UP,500
PSC_ACCZ_P,0.3
PSC_POSZ_P,2
PSC_VELZ_P,7
SCHED_LOOP_RATE,500
SERVO_BLH_AUTO,1
SERVO_BLH_DEBUG,1
BATT_AMP_PERVLT,17
BATT_CAPACITY,3300
BATT_CURR_PIN,12
BATT_LOW_VOLT,10
BATT_VOLT_MULT,11
BATT_VOLT_PIN,13
#NOTE: Holybro Kospi1 default params for Copter-3.6 (and higher)
ACRO_RP_P,9
ACRO_TRAINER,0
AHRS_EKF_TYPE,3
ATC_ACCEL_P_MAX,256000
ATC_ACCEL_R_MAX,364000
ATC_ACCEL_Y_MAX,89000
ATC_ANGLE_BOOST,0
ATC_ANG_PIT_P,25.0
ATC_ANG_RLL_P,25.0
ATC_ANG_YAW_P,14.1
ATC_INPUT_TC,0.05
ATC_RAT_PIT_D,0.001486
ATC_RAT_PIT_FILT,40
ATC_RAT_PIT_FLTD,40
ATC_RAT_PIT_I,0.066914
ATC_RAT_PIT_P,0.066914
ATC_RAT_RLL_D,0.001125
ATC_RAT_RLL_FILT,40
ATC_RAT_RLL_FLTD,40
ATC_RAT_RLL_I,0.054774
ATC_RAT_RLL_P,0.054774
ATC_RAT_YAW_FILT,3.491686
ATC_RAT_YAW_FLTE,3.491686
ATC_RAT_YAW_I,0.02087
ATC_RAT_YAW_P,0.208696
BATT_MONITOR,4
BRD_PWM_COUNT,8
EK2_ENABLE,0
EK3_ENABLE,1
FRAME_CLASS,1
INS_ACCEL_FILTER,10
INS_GYRO_FILTER,80
LOG_BITMASK,65534
MOT_PWM_MAX,2000
MOT_PWM_MIN,1000
MOT_PWM_TYPE,4
MOT_SPIN_MIN,0.1
MOT_THST_EXPO,0.5
MOT_THST_HOVER,0.125
PILOT_ACCEL_Z,800
PILOT_SPEED_UP,500
PSC_ACCZ_P,0.3
PSC_POSZ_P,2
PSC_VELZ_P,7
SCHED_LOOP_RATE,500
SERVO_BLH_AUTO,1
SERVO_BLH_DEBUG,1
BATT_AMP_PERVLT,17
BATT_CAPACITY,3300
BATT_CURR_PIN,12
BATT_LOW_VOLT,10
BATT_VOLT_MULT,11
BATT_VOLT_PIN,13

78
Tools/Frame_params/ThunderTiger-ToyotaHilux-Rover.param

@ -1,39 +1,39 @@ @@ -1,39 +1,39 @@
#NOTE: Thunder Tiger Toyota Hilux Rover param file
ACRO_TURN_RATE,80
ATC_ACCEL_MAX,1
ATC_BRAKE,1
ATC_SPEED_I,0.2
ATC_SPEED_P,0.2
ATC_STR_RAT_FF,1.2
ATC_STR_RAT_I,0.4
ATC_STR_RAT_P,0.4
COMPASS_ORIENT,4
CRUISE_SPEED,1.43
CRUISE_THROTTLE,70
EK2_YAW_M_NSE,0.7
FRAME_CLASS,1
MOT_PWM_FREQ,16
MOT_PWM_TYPE,0
MOT_SAFE_DISARM,0
MOT_SLEWRATE,100
MOT_THR_MAX,100
MOT_THR_MIN,20
MOT_THST_EXPO,0
MOT_VEC_THR_BASE,0
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
PILOT_STEER_TYPE,0
SERIAL1_BAUD,921
SERIAL1_PROTOCOL,2
SERVO1_FUNCTION,26
SERVO1_MAX,1900
SERVO1_MIN,1100
SERVO1_REVERSED,1
SERVO1_TRIM,1500
SERVO3_FUNCTION,70
SERVO3_MAX,2000
SERVO3_MIN,1000
SERVO3_REVERSED,0
SERVO3_TRIM,1500
ATC_TURN_MAX_G,0.3
#NOTE: Thunder Tiger Toyota Hilux Rover param file
ACRO_TURN_RATE,80
ATC_ACCEL_MAX,1
ATC_BRAKE,1
ATC_SPEED_I,0.2
ATC_SPEED_P,0.2
ATC_STR_RAT_FF,1.2
ATC_STR_RAT_I,0.4
ATC_STR_RAT_P,0.4
COMPASS_ORIENT,4
CRUISE_SPEED,1.43
CRUISE_THROTTLE,70
EK2_YAW_M_NSE,0.7
FRAME_CLASS,1
MOT_PWM_FREQ,16
MOT_PWM_TYPE,0
MOT_SAFE_DISARM,0
MOT_SLEWRATE,100
MOT_THR_MAX,100
MOT_THR_MIN,20
MOT_THST_EXPO,0
MOT_VEC_THR_BASE,0
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
PILOT_STEER_TYPE,0
SERIAL1_BAUD,921
SERIAL1_PROTOCOL,2
SERVO1_FUNCTION,26
SERVO1_MAX,1900
SERVO1_MIN,1100
SERVO1_REVERSED,1
SERVO1_TRIM,1500
SERVO3_FUNCTION,70
SERVO3_MAX,2000
SERVO3_MIN,1000
SERVO3_REVERSED,0
SERVO3_TRIM,1500
ATC_TURN_MAX_G,0.3

BIN
Tools/Frame_params/XPlane/NACA_64_xxx_Airfoils_from_TR824.zip

Binary file not shown.

64
Tools/Frame_params/amovlab-p200.param

@ -1,32 +1,32 @@ @@ -1,32 +1,32 @@
#NOTE: Amovlab P200 params for ArduPilot Copter 4.0.0
ANGLE_MAX,3500
ACRO_YAW_P,1.8
ATC_ACCEL_P_MAX,110000
ATC_ACCEL_R_MAX,110000
ATC_ACCEL_Y_MAX,17000
ATC_ANG_PIT_P,7.6
ATC_ANG_RLL_P,7.6
ATC_ANG_YAW_P,4.7
ATC_RAT_PIT_D,0.0015
ATC_RAT_PIT_I,0.09
ATC_RAT_PIT_P,0.09
ATC_RAT_RLL_D,0.0015
ATC_RAT_RLL_I,0.09
ATC_RAT_RLL_P,0.09
ATC_RAT_YAW_P,0.8
ATC_RAT_YAW_I,0.08
ATC_RAT_YAW_FLTE,1.0
BATT_AMP_PERVLT,39.877
BATT_CAPACITY,3300
BATT_MONITOR,4
BRD_SAFETYENABLE,0
FRAME_CLASS,1
FRAME_TYPE,1
GPS_TYPE,2
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,12.6
MOT_BAT_VOLT_MIN,9.9
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.11
MOT_THST_HOVER,0.36
#NOTE: Amovlab P200 params for ArduPilot Copter 4.0.0
ANGLE_MAX,3500
ACRO_YAW_P,1.8
ATC_ACCEL_P_MAX,110000
ATC_ACCEL_R_MAX,110000
ATC_ACCEL_Y_MAX,17000
ATC_ANG_PIT_P,7.6
ATC_ANG_RLL_P,7.6
ATC_ANG_YAW_P,4.7
ATC_RAT_PIT_D,0.0015
ATC_RAT_PIT_I,0.09
ATC_RAT_PIT_P,0.09
ATC_RAT_RLL_D,0.0015
ATC_RAT_RLL_I,0.09
ATC_RAT_RLL_P,0.09
ATC_RAT_YAW_P,0.8
ATC_RAT_YAW_I,0.08
ATC_RAT_YAW_FLTE,1.0
BATT_AMP_PERVLT,39.877
BATT_CAPACITY,3300
BATT_MONITOR,4
BRD_SAFETYENABLE,0
FRAME_CLASS,1
FRAME_TYPE,1
GPS_TYPE,2
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,12.6
MOT_BAT_VOLT_MIN,9.9
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.11
MOT_THST_HOVER,0.36

46
Tools/Frame_params/boogie-board-boat.param

@ -1,23 +1,23 @@ @@ -1,23 +1,23 @@
#NOTE: BoogieBoard Boat Sep2020
ATC_ACCEL_MAX,1
ATC_SPEED_I,0.1
ATC_SPEED_P,0.1
ATC_STR_RAT_FF,0.18
ATC_STR_RAT_MAX,200
ATC_STR_RAT_P,0.2
BRD_SAFETYENABLE,0
CRUISE_SPEED,1.90
CRUISE_THROTTLE,75
FRAME_CLASS,2
FRAME_TYPE,0
FS_ACTION,1
MOT_THR_MIN,5
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
PILOT_STEER_TYPE,0
SERVO1_FUNCTION,73
SERVO3_FUNCTION,74
ATC_TURN_MAX_G,0.3
WP_OVERSHOOT,2
WP_SPEED,1.5
#NOTE: BoogieBoard Boat Sep2020
ATC_ACCEL_MAX,1
ATC_SPEED_I,0.1
ATC_SPEED_P,0.1
ATC_STR_RAT_FF,0.18
ATC_STR_RAT_MAX,200
ATC_STR_RAT_P,0.2
BRD_SAFETYENABLE,0
CRUISE_SPEED,1.90
CRUISE_THROTTLE,75
FRAME_CLASS,2
FRAME_TYPE,0
FS_ACTION,1
MOT_THR_MIN,5
NAVL1_DAMPING,0.75
NAVL1_PERIOD,8
NAVL1_XTRACK_I,0.02
PILOT_STEER_TYPE,0
SERVO1_FUNCTION,73
SERVO3_FUNCTION,74
ATC_TURN_MAX_G,0.3
WP_OVERSHOOT,2
WP_SPEED,1.5

84
Tools/Frame_params/deset-mapping-boat.param

@ -1,42 +1,42 @@ @@ -1,42 +1,42 @@
#NOTE: JapanDrones DeSET mapping boat parameters for ArduPilor Rover-4.2 (or higher). Serial1:Herelink receiver, Serial2:Torqeedo motor adapter, Serial3:dAISy2+, Serial4:NMEA Sonar
ACRO_TURN_RATE,60
AIS_TYPE,1
ATC_ACCEL_MAX,0.3
ATC_BRAKE,0
ATC_SPEED_FLTE,5
ATC_SPEED_I,0.2
ATC_SPEED_IMAX,0.5
ATC_SPEED_P,0.2
ATC_STR_ACC_MAX,120
ATC_STR_ANG_P,2
ATC_STR_RAT_FF,0.4
ATC_STR_RAT_FLTE,5
ATC_STR_RAT_I,0.2
ATC_STR_RAT_MAX,90
ATC_STR_RAT_P,0.15
ATC_TURN_MAX_G,0.2
BATT_MONITOR,23
BRD_SAFETYENABLE,0
CRUISE_SPEED,3.1
CRUISE_THROTTLE,100
FRAME_CLASS,2
FRAME_TYPE,0
MOT_SLEWRATE,25
MOT_VEC_ANGLEMAX,30
NAVL1_DAMPING,0.8
NAVL1_PERIOD,16
RNGFND1_MAX_CM,20000
RNGFND1_MIN_CM,0
RNGFND1_TYPE,17
SERIAL2_BAUD,19
SERIAL2_PROTOCOL,39
SERIAL3_BAUD,38
SERIAL3_PROTOCOL,40
SERIAL4_BAUD,9
SERIAL4_PROTOCOL,9
SR0_ADSB,1
SR1_ADSB,1
TRQD_SLEW_TIME,3
TRQD_TYPE,2
WP_RADIUS,2
WP_SPEED,1.5
#NOTE: JapanDrones DeSET mapping boat parameters for ArduPilor Rover-4.2 (or higher). Serial1:Herelink receiver, Serial2:Torqeedo motor adapter, Serial3:dAISy2+, Serial4:NMEA Sonar
ACRO_TURN_RATE,60
AIS_TYPE,1
ATC_ACCEL_MAX,0.3
ATC_BRAKE,0
ATC_SPEED_FLTE,5
ATC_SPEED_I,0.2
ATC_SPEED_IMAX,0.5
ATC_SPEED_P,0.2
ATC_STR_ACC_MAX,120
ATC_STR_ANG_P,2
ATC_STR_RAT_FF,0.4
ATC_STR_RAT_FLTE,5
ATC_STR_RAT_I,0.2
ATC_STR_RAT_MAX,90
ATC_STR_RAT_P,0.15
ATC_TURN_MAX_G,0.2
BATT_MONITOR,23
BRD_SAFETYENABLE,0
CRUISE_SPEED,3.1
CRUISE_THROTTLE,100
FRAME_CLASS,2
FRAME_TYPE,0
MOT_SLEWRATE,25
MOT_VEC_ANGLEMAX,30
NAVL1_DAMPING,0.8
NAVL1_PERIOD,16
RNGFND1_MAX_CM,20000
RNGFND1_MIN_CM,0
RNGFND1_TYPE,17
SERIAL2_BAUD,19
SERIAL2_PROTOCOL,39
SERIAL3_BAUD,38
SERIAL3_PROTOCOL,40
SERIAL4_BAUD,9
SERIAL4_PROTOCOL,9
SR0_ADSB,1
SR1_ADSB,1
TRQD_SLEW_TIME,3
TRQD_TYPE,2
WP_RADIUS,2
WP_SPEED,1.5

90
Tools/Frame_params/eLAB_EX1050_AC34.param

@ -1,45 +1,45 @@ @@ -1,45 +1,45 @@
#NOTE: EnRoute EX1050 parameter defaults (Copter-3.4 and higher)
ACRO_YAW_P,2.0
ANGLE_MAX,3000
ATC_ACCEL_P_MAX,41300
ATC_ACCEL_R_MAX,43600
ATC_ACCEL_Y_MAX,10800
ATC_ANG_PIT_P,7.2
ATC_ANG_RLL_P,6.3
ATC_ANG_YAW_P,4.5
ATC_RAT_PIT_D,0.0128
ATC_RAT_PIT_FILT,10.0
ATC_RAT_PIT_FLTD,10.0
ATC_RAT_PIT_I,0.144
ATC_RAT_PIT_IMAX,0.2
ATC_RAT_PIT_P,0.144
ATC_RAT_RLL_D,0.01386
ATC_RAT_RLL_FILT,10.0
ATC_RAT_RLL_FLTD,10.0
ATC_RAT_RLL_I,0.1523
ATC_RAT_RLL_P,0.1523
ATC_RAT_YAW_I,0.018
ATC_RAT_YAW_IMAX,0.17
ATC_RAT_YAW_P,0.18
BATT_MONITOR,3
BATT_VOLT_MULT,15.8191
BATT_AMP_PERVOLT,54.64
BATT_CAPACITY,13500
BRD_SAFETYENABLE,0
FRAME,1
FRAME_CLASS,1
FS_BATT_ENABLE,1
FS_BATT_VOLTAGE,43
GND_EFFECT_COMP,1
GPS_TYPE,2
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.11
MOT_THST_HOVER,0.30
MOT_THST_EXPO,0.7
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,21.0
PILOT_THR_BHV,1
WPNAV_SPEED,500
WPNAV_LOIT_SPEED,800
WPNAV_LOIT_MAXA,250
WPNAV_LOIT_MINA,25
#NOTE: EnRoute EX1050 parameter defaults (Copter-3.4 and higher)
ACRO_YAW_P,2.0
ANGLE_MAX,3000
ATC_ACCEL_P_MAX,41300
ATC_ACCEL_R_MAX,43600
ATC_ACCEL_Y_MAX,10800
ATC_ANG_PIT_P,7.2
ATC_ANG_RLL_P,6.3
ATC_ANG_YAW_P,4.5
ATC_RAT_PIT_D,0.0128
ATC_RAT_PIT_FILT,10.0
ATC_RAT_PIT_FLTD,10.0
ATC_RAT_PIT_I,0.144
ATC_RAT_PIT_IMAX,0.2
ATC_RAT_PIT_P,0.144
ATC_RAT_RLL_D,0.01386
ATC_RAT_RLL_FILT,10.0
ATC_RAT_RLL_FLTD,10.0
ATC_RAT_RLL_I,0.1523
ATC_RAT_RLL_P,0.1523
ATC_RAT_YAW_I,0.018
ATC_RAT_YAW_IMAX,0.17
ATC_RAT_YAW_P,0.18
BATT_MONITOR,3
BATT_VOLT_MULT,15.8191
BATT_AMP_PERVOLT,54.64
BATT_CAPACITY,13500
BRD_SAFETYENABLE,0
FRAME,1
FRAME_CLASS,1
FS_BATT_ENABLE,1
FS_BATT_VOLTAGE,43
GND_EFFECT_COMP,1
GPS_TYPE,2
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.11
MOT_THST_HOVER,0.30
MOT_THST_EXPO,0.7
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,21.0
PILOT_THR_BHV,1
WPNAV_SPEED,500
WPNAV_LOIT_SPEED,800
WPNAV_LOIT_MAXA,250
WPNAV_LOIT_MINA,25

134
Tools/Frame_params/eLAB_EX700_AC34.param

@ -1,67 +1,67 @@ @@ -1,67 +1,67 @@
#NOTE: EnRoute EX700 parameter defaults (Copter-3.4 and higher)
ACRO_YAW_P,3.0
ANGLE_MAX,3000
AUTOTUNE_AGGR,0.1
ATC_ACCEL_P_MAX,41300
ATC_ACCEL_R_MAX,43600
ATC_ACCEL_Y_MAX,10800
ATC_ANG_PIT_P,6.89
ATC_ANG_RLL_P,6.01
ATC_ANG_YAW_P,5.48
ATC_RAT_PIT_D,0.01636
ATC_RAT_PIT_FILT,10.0
ATC_RAT_PIT_FLTD,10.0
ATC_RAT_PIT_I,0.1379
ATC_RAT_PIT_P,0.1379
ATC_RAT_RLL_D,0.00683
ATC_RAT_RLL_FILT,10.0
ATC_RAT_RLL_FLTD,10.0
ATC_RAT_RLL_I,0.0814
ATC_RAT_RLL_P,0.0814
ATC_RAT_YAW_I,0.044
ATC_RAT_YAW_P,0.441
BATT_MONITOR,4
BATT_AMP_PERVOLT,54.64
BATT_CAPACITY,13500
BRD_SAFETYENABLE,0
BRD_SER1_RTSCTS,0
BRD_SER2_RTSCTS,0
FLOW_ORIENT_YAW,-9000
FRAME,1
FRAME_CLASS,1
FS_BATT_ENABLE,1
FS_BATT_VOLTAGE,21
GND_EFFECT_COMP,1
GPS_TYPE,2
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.12
MOT_THST_HOVER,0.25
MOT_THST_EXPO,0.7
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,21.0
RNGFND_MAX_CM,5000
RNGFND_MIN_CM,5
RNGFND_SCALING,1
RNGFND_TYPE,8
PILOT_THR_BHV,1
PRX_ORIENT,1
PRX_TYPE,1
PRX_YAW_CORR,28
PRX_IGN_ANG1,52
PRX_IGN_WID2,10
PRX_IGN_ANG2,144
PRX_IGN_WID2,10
PRX_IGN_ANG3,222
PRX_IGN_WID3,10
PRX_IGN_ANG3,312
PRX_IGN_WID3,10
SERIAL1_PROTOCOL,9
SERIAL1_BAUD,19200
SERIAL2_PROTOCOL,1
SERIAL2_BAUD,921
SERIAL4_PROTOCOL,11
SERIAL4_BAUD,115
WPNAV_SPEED,1000
WPNAV_LOIT_SPEED,1000
WPNAV_LOIT_MAXA,230
WPNAV_LOIT_MINA,100
#NOTE: EnRoute EX700 parameter defaults (Copter-3.4 and higher)
ACRO_YAW_P,3.0
ANGLE_MAX,3000
AUTOTUNE_AGGR,0.1
ATC_ACCEL_P_MAX,41300
ATC_ACCEL_R_MAX,43600
ATC_ACCEL_Y_MAX,10800
ATC_ANG_PIT_P,6.89
ATC_ANG_RLL_P,6.01
ATC_ANG_YAW_P,5.48
ATC_RAT_PIT_D,0.01636
ATC_RAT_PIT_FILT,10.0
ATC_RAT_PIT_FLTD,10.0
ATC_RAT_PIT_I,0.1379
ATC_RAT_PIT_P,0.1379
ATC_RAT_RLL_D,0.00683
ATC_RAT_RLL_FILT,10.0
ATC_RAT_RLL_FLTD,10.0
ATC_RAT_RLL_I,0.0814
ATC_RAT_RLL_P,0.0814
ATC_RAT_YAW_I,0.044
ATC_RAT_YAW_P,0.441
BATT_MONITOR,4
BATT_AMP_PERVOLT,54.64
BATT_CAPACITY,13500
BRD_SAFETYENABLE,0
BRD_SER1_RTSCTS,0
BRD_SER2_RTSCTS,0
FLOW_ORIENT_YAW,-9000
FRAME,1
FRAME_CLASS,1
FS_BATT_ENABLE,1
FS_BATT_VOLTAGE,21
GND_EFFECT_COMP,1
GPS_TYPE,2
MOT_SPIN_ARM,0.08
MOT_SPIN_MIN,0.12
MOT_THST_HOVER,0.25
MOT_THST_EXPO,0.7
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,21.0
RNGFND_MAX_CM,5000
RNGFND_MIN_CM,5
RNGFND_SCALING,1
RNGFND_TYPE,8
PILOT_THR_BHV,1
PRX_ORIENT,1
PRX_TYPE,1
PRX_YAW_CORR,28
PRX_IGN_ANG1,52
PRX_IGN_WID2,10
PRX_IGN_ANG2,144
PRX_IGN_WID2,10
PRX_IGN_ANG3,222
PRX_IGN_WID3,10
PRX_IGN_ANG3,312
PRX_IGN_WID3,10
SERIAL1_PROTOCOL,9
SERIAL1_BAUD,19200
SERIAL2_PROTOCOL,1
SERIAL2_BAUD,921
SERIAL4_PROTOCOL,11
SERIAL4_BAUD,115
WPNAV_SPEED,1000
WPNAV_LOIT_SPEED,1000
WPNAV_LOIT_MAXA,230
WPNAV_LOIT_MINA,100

192
Tools/Frame_params/eLAB_LAB470_AC35.param

@ -1,96 +1,96 @@ @@ -1,96 +1,96 @@
#NOTE: eLAB LAB470 quadcopter on Copter-3.5
ACRO_YAW_P,3.0
AHRS_ORIENTATION,14
ANGLE_MAX,3000
ARMING_VOLT_MIN,22
ATC_ACCEL_P_MAX,38000
ATC_ACCEL_R_MAX,41000
ATC_ACCEL_Y_MAX,18000
ATC_ANG_PIT_P,8
ATC_ANG_RLL_P,8
ATC_ANG_YAW_P,4.5
ATC_RAT_PIT_D,0.009977
ATC_RAT_PIT_FILT,10
ATC_RAT_PIT_FLTD,10
ATC_RAT_PIT_I,0.1022741
ATC_RAT_PIT_P,0.1022741
ATC_RAT_RLL_D,0.009617
ATC_RAT_RLL_FILT,10
ATC_RAT_RLL_FLTD,10
ATC_RAT_RLL_I,0.0827849
ATC_RAT_RLL_P,0.0827849
ATC_RAT_YAW_D,0
ATC_RAT_YAW_FILT,2.5
ATC_RAT_YAW_FLTE,2.5
ATC_RAT_YAW_I,0.018
ATC_RAT_YAW_P,0.18
ATC_RATE_FF_ENAB,1
BATT_CAPACITY,5400
BATT_CURR_PIN,3
BATT_MONITOR,3
BATT_VOLT_MULT,7.699197
BATT_VOLT_PIN,2
RC7_OPTION,4
FENCE_ACTION,1
FENCE_ALT_MAX,100
FENCE_ENABLE,0
FENCE_RADIUS,300
FLTMODE1,0
FLTMODE2,0
FLTMODE3,0
FLTMODE4,2
FLTMODE5,0
FLTMODE6,5
FRAME_CLASS,1
FRAME_TYPE,1
FS_BATT_ENABLE,1
FS_BATT_MAH,0
FS_BATT_VOLTAGE,21
FS_THR_ENABLE,1
GND_EFFECT_COMP,0
GPS_POS1_X,0
GPS_POS1_Y,0
GPS_POS1_Z,0
GPS_TYPE,2
LOG_BACKEND_TYPE,1
MNT_ANGMAX_PAN,4500
MNT_ANGMAX_ROL,3000
MNT_ANGMAX_TIL,0
MNT_ANGMIN_PAN,-4500
MNT_ANGMIN_ROL,-3000
MNT_ANGMIN_TIL,-9000
MNT_LEAD_PTCH,0
MNT_LEAD_RLL,0
MNT_RC_IN_TILT,6
MNT_TYPE,3
MOT_SPIN_ARM,0.08
MOT_SPIN_MAX,0.95
MOT_SPIN_MIN,0.12
MOT_THST_EXPO,0.65
MOT_THST_HOVER,0.22
PILOT_THR_BHV,1
PILOT_VELZ_MAX,250
RC_FEEL_RP,50
RTL_ALT,2000
SERIAL1_BAUD,57
SERIAL1_PROTOCOL,1
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERIAL3_BAUD,57
SERIAL3_PROTOCOL,5
SERIAL4_BAUD,115
SERIAL4_PROTOCOL,7
TERRAIN_ENABLE,1
TERRAIN_FOLLOW,0
TERRAIN_SPACING,30
WP_YAW_BEHAVIOR,1
WPNAV_ACCEL,100
WPNAV_ACCEL_Z,100
WPNAV_LOIT_JERK,1000
WPNAV_LOIT_MAXA,450
WPNAV_LOIT_MINA,175
WPNAV_LOIT_SPEED,1000
WPNAV_RADIUS,200
WPNAV_SPEED,1000
WPNAV_SPEED_DN,150
WPNAV_SPEED_UP,250
#NOTE: eLAB LAB470 quadcopter on Copter-3.5
ACRO_YAW_P,3.0
AHRS_ORIENTATION,14
ANGLE_MAX,3000
ARMING_VOLT_MIN,22
ATC_ACCEL_P_MAX,38000
ATC_ACCEL_R_MAX,41000
ATC_ACCEL_Y_MAX,18000
ATC_ANG_PIT_P,8
ATC_ANG_RLL_P,8
ATC_ANG_YAW_P,4.5
ATC_RAT_PIT_D,0.009977
ATC_RAT_PIT_FILT,10
ATC_RAT_PIT_FLTD,10
ATC_RAT_PIT_I,0.1022741
ATC_RAT_PIT_P,0.1022741
ATC_RAT_RLL_D,0.009617
ATC_RAT_RLL_FILT,10
ATC_RAT_RLL_FLTD,10
ATC_RAT_RLL_I,0.0827849
ATC_RAT_RLL_P,0.0827849
ATC_RAT_YAW_D,0
ATC_RAT_YAW_FILT,2.5
ATC_RAT_YAW_FLTE,2.5
ATC_RAT_YAW_I,0.018
ATC_RAT_YAW_P,0.18
ATC_RATE_FF_ENAB,1
BATT_CAPACITY,5400
BATT_CURR_PIN,3
BATT_MONITOR,3
BATT_VOLT_MULT,7.699197
BATT_VOLT_PIN,2
RC7_OPTION,4
FENCE_ACTION,1
FENCE_ALT_MAX,100
FENCE_ENABLE,0
FENCE_RADIUS,300
FLTMODE1,0
FLTMODE2,0
FLTMODE3,0
FLTMODE4,2
FLTMODE5,0
FLTMODE6,5
FRAME_CLASS,1
FRAME_TYPE,1
FS_BATT_ENABLE,1
FS_BATT_MAH,0
FS_BATT_VOLTAGE,21
FS_THR_ENABLE,1
GND_EFFECT_COMP,0
GPS_POS1_X,0
GPS_POS1_Y,0
GPS_POS1_Z,0
GPS_TYPE,2
LOG_BACKEND_TYPE,1
MNT_ANGMAX_PAN,4500
MNT_ANGMAX_ROL,3000
MNT_ANGMAX_TIL,0
MNT_ANGMIN_PAN,-4500
MNT_ANGMIN_ROL,-3000
MNT_ANGMIN_TIL,-9000
MNT_LEAD_PTCH,0
MNT_LEAD_RLL,0
MNT_RC_IN_TILT,6
MNT_TYPE,3
MOT_SPIN_ARM,0.08
MOT_SPIN_MAX,0.95
MOT_SPIN_MIN,0.12
MOT_THST_EXPO,0.65
MOT_THST_HOVER,0.22
PILOT_THR_BHV,1
PILOT_VELZ_MAX,250
RC_FEEL_RP,50
RTL_ALT,2000
SERIAL1_BAUD,57
SERIAL1_PROTOCOL,1
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERIAL3_BAUD,57
SERIAL3_PROTOCOL,5
SERIAL4_BAUD,115
SERIAL4_PROTOCOL,7
TERRAIN_ENABLE,1
TERRAIN_FOLLOW,0
TERRAIN_SPACING,30
WP_YAW_BEHAVIOR,1
WPNAV_ACCEL,100
WPNAV_ACCEL_Z,100
WPNAV_LOIT_JERK,1000
WPNAV_LOIT_MAXA,450
WPNAV_LOIT_MINA,175
WPNAV_LOIT_SPEED,1000
WPNAV_RADIUS,200
WPNAV_SPEED,1000
WPNAV_SPEED_DN,150
WPNAV_SPEED_UP,250

90
Tools/Frame_params/eLAB_VEK_AI_Rover.param

@ -1,45 +1,45 @@ @@ -1,45 +1,45 @@
#NOTE: eLAB VEK AI - APM:Rover V3.2
AHRS_EKF_TYPE,3
ATC_STR_RAT_FF,0.15
ATC_STR_RAT_P,0.0
ATC_STR_RAT_I,0.2
BATT_CURR_PIN,-1
BATT_VOLT_PIN,-1
CRUISE_SPEED,1.0
EK2_ENABLE,0
EK3_ENABLE,1
GPS_TYPE,2
MIS_RESTART,1
MODE_CH,5
MODE1,10
MODE2,0
MODE3,0
MODE4,3
MODE5,10
MODE6,0
MOT_THST_EXPO,-0.5
NAVL1_PERIOD,12
PIVOT_TURN_ANGLE,60
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERVO1_FUNCTION,73
SERVO1_MAX,1920
SERVO1_MIN,1120
SERVO1_REVERSED,0
SERVO1_TRIM,1520
SERVO3_FUNCTION,74
SERVO3_MAX,1920
SERVO3_MIN,1120
SERVO3_REVERSED,1
SERVO3_TRIM,1533
SPEED_TURN_GAIN,25
STEER2SRV_D,0.01
STEER2SRV_I,0.003
STEER2SRV_P,0.3
THR_SLEWRATE,50
ATC_TURN_MAX_G,0.21
VISO_ORIENT,0
VISO_POS_X,0
VISO_POS_Y,0
VISO_POS_Z,0
VISO_TYPE,1
#NOTE: eLAB VEK AI - APM:Rover V3.2
AHRS_EKF_TYPE,3
ATC_STR_RAT_FF,0.15
ATC_STR_RAT_P,0.0
ATC_STR_RAT_I,0.2
BATT_CURR_PIN,-1
BATT_VOLT_PIN,-1
CRUISE_SPEED,1.0
EK2_ENABLE,0
EK3_ENABLE,1
GPS_TYPE,2
MIS_RESTART,1
MODE_CH,5
MODE1,10
MODE2,0
MODE3,0
MODE4,3
MODE5,10
MODE6,0
MOT_THST_EXPO,-0.5
NAVL1_PERIOD,12
PIVOT_TURN_ANGLE,60
SERIAL2_BAUD,921
SERIAL2_PROTOCOL,1
SERVO1_FUNCTION,73
SERVO1_MAX,1920
SERVO1_MIN,1120
SERVO1_REVERSED,0
SERVO1_TRIM,1520
SERVO3_FUNCTION,74
SERVO3_MAX,1920
SERVO3_MIN,1120
SERVO3_REVERSED,1
SERVO3_TRIM,1533
SPEED_TURN_GAIN,25
STEER2SRV_D,0.01
STEER2SRV_I,0.003
STEER2SRV_P,0.3
THR_SLEWRATE,50
ATC_TURN_MAX_G,0.21
VISO_ORIENT,0
VISO_POS_X,0
VISO_POS_Y,0
VISO_POS_Z,0
VISO_TYPE,1

58
Tools/Frame_params/hexsoon-edu450.param

@ -1,29 +1,29 @@ @@ -1,29 +1,29 @@
#NOTE: Hexsoon EDU450 params for ArduPilot Copter 4.0.0
ANGLE_MAX,3500
ACRO_YAW_P,1.5
ATC_ACCEL_P_MAX,70000
ATC_ACCEL_R_MAX,70000
ATC_ACCEL_Y_MAX,12000
ATC_ANG_PIT_P,11
ATC_ANG_RLL_P,11
ATC_ANG_YAW_P,7.2
ATC_RAT_PIT_D,0.00602
ATC_RAT_PIT_I,0.17
ATC_RAT_PIT_P,0.17
ATC_RAT_RLL_D,0.00602
ATC_RAT_RLL_I,0.17
ATC_RAT_RLL_P,0.17
ATC_RAT_YAW_P,0.6
ATC_RAT_YAW_I,0.06
ATC_RAT_YAW_FLTE,1.0
BATT_AMP_PERVLT,39.877
BATT_CAPACITY,5300
BATT_MONITOR,4
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,12.6
MOT_BAT_VOLT_MIN,9.9
MOT_SPIN_ARM,0.11
MOT_SPIN_MIN,0.13
MOT_THST_HOVER,0.36
#NOTE: Hexsoon EDU450 params for ArduPilot Copter 4.0.0
ANGLE_MAX,3500
ACRO_YAW_P,1.5
ATC_ACCEL_P_MAX,70000
ATC_ACCEL_R_MAX,70000
ATC_ACCEL_Y_MAX,12000
ATC_ANG_PIT_P,11
ATC_ANG_RLL_P,11
ATC_ANG_YAW_P,7.2
ATC_RAT_PIT_D,0.00602
ATC_RAT_PIT_I,0.17
ATC_RAT_PIT_P,0.17
ATC_RAT_RLL_D,0.00602
ATC_RAT_RLL_I,0.17
ATC_RAT_RLL_P,0.17
ATC_RAT_YAW_P,0.6
ATC_RAT_YAW_I,0.06
ATC_RAT_YAW_FLTE,1.0
BATT_AMP_PERVLT,39.877
BATT_CAPACITY,5300
BATT_MONITOR,4
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,40
MOT_BAT_VOLT_MAX,12.6
MOT_BAT_VOLT_MIN,9.9
MOT_SPIN_ARM,0.11
MOT_SPIN_MIN,0.13
MOT_THST_HOVER,0.36

58
Tools/Frame_params/hexsoon-td650.param

@ -1,29 +1,29 @@ @@ -1,29 +1,29 @@
#NOTE: Hexsoon TD650 params for ArduPilot Copter 4.1
ANGLE_MAX,3500
ACRO_YAW_P,2.6
ATC_ACCEL_P_MAX,86000
ATC_ACCEL_R_MAX,86000
ATC_ACCEL_Y_MAX,23400
ATC_RAT_PIT_FLTD,17
ATC_RAT_PIT_FLTT,17
ATC_RAT_PIT_D,0.0034
ATC_RAT_PIT_I,0.12
ATC_RAT_PIT_P,0.12
ATC_RAT_RLL_D,0.0034
ATC_RAT_RLL_FLTD,17
ATC_RAT_RLL_FLTT,17
ATC_RAT_RLL_I,0.12
ATC_RAT_RLL_P,0.12
ATC_RAT_YAW_FLTE,2
BATT_MONITOR,4
BATT_VOLT_MULT,12.02
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,34
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,19.8
MOT_THST_EXPO,0.68
MOT_THST_HOVER,0.2288489
PSC_ACCZ_I,0.5
PSC_ACCZ_P,0.3
#NOTE: Hexsoon TD650 params for ArduPilot Copter 4.1
ANGLE_MAX,3500
ACRO_YAW_P,2.6
ATC_ACCEL_P_MAX,86000
ATC_ACCEL_R_MAX,86000
ATC_ACCEL_Y_MAX,23400
ATC_RAT_PIT_FLTD,17
ATC_RAT_PIT_FLTT,17
ATC_RAT_PIT_D,0.0034
ATC_RAT_PIT_I,0.12
ATC_RAT_PIT_P,0.12
ATC_RAT_RLL_D,0.0034
ATC_RAT_RLL_FLTD,17
ATC_RAT_RLL_FLTT,17
ATC_RAT_RLL_I,0.12
ATC_RAT_RLL_P,0.12
ATC_RAT_YAW_FLTE,2
BATT_MONITOR,4
BATT_VOLT_MULT,12.02
FRAME_CLASS,1
FRAME_TYPE,1
INS_GYRO_FILTER,34
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,19.8
MOT_THST_EXPO,0.68
MOT_THST_HOVER,0.2288489
PSC_ACCZ_I,0.5
PSC_ACCZ_P,0.3

146
Tools/Frame_params/iflight-chimera7-4.2.param

@ -1,73 +1,73 @@ @@ -1,73 +1,73 @@
#NOTE: iFlight Chimera7 params for ArduPilot Copter 4.2
ACRO_RP_EXPO,0.6
ACRO_RP_RATE,600
ACRO_Y_EXPO,0.6
ACRO_Y_RATE,600
ATC_ACCEL_P_MAX,281062.5
ATC_ACCEL_R_MAX,301679.8
ATC_ACCEL_Y_MAX,72000
ATC_ANG_PIT_P,18
ATC_ANG_RLL_P,18
ATC_ANG_YAW_P,11
ATC_RAT_PIT_D,0.001879093
ATC_RAT_PIT_FLTD,60
ATC_RAT_PIT_FLTT,30
ATC_RAT_PIT_I,0.09663188
ATC_RAT_PIT_P,0.09663188
ATC_RAT_RLL_D,0.001453624
ATC_RAT_RLL_FLTD,75
ATC_RAT_RLL_FLTT,30
ATC_RAT_RLL_I,0.07706726
ATC_RAT_RLL_P,0.07706726
ATC_RAT_YAW_D,0.02
ATC_RAT_YAW_FF,0.0043
ATC_RAT_YAW_FLTD,60
ATC_RAT_YAW_FLTE,1.887445
ATC_RAT_YAW_FLTT,30
ATC_RAT_YAW_I,0.01927038
ATC_RAT_YAW_P,0.1927038
BATT_AMP_OFFSET,-0.04308
BATT_AMP_PERVLT,52.706
BATT_CURR_PIN,11
BATT_LOW_VOLT,21.6
BATT_MONITOR,4
COMPASS_AUTO_ROT,0
COMPASS_CUS_PIT,-15
COMPASS_CUS_ROLL,0
COMPASS_CUS_YAW,180
COMPASS_ORIENT,100
EK3_PRIMARY,1
EK3_IMU_MASK,2
FRAME_CLASS,1
FRAME_TYPE,12
INS_GYRO_FILTER,150
INS_HNTCH_BW,20
INS_HNTCH_ENABLE,1
INS_HNTCH_FREQ,40
INS_HNTCH_HMNCS,1
INS_HNTCH_MODE,3
INS_HNTCH_OPTS,6
INS_HNTCH_REF,1
INS_HNTC2_BW,75
INS_HNTC2_ENABLE,1
INS_HNTC2_FREQ,150
INS_HNTC2_HMNCS,1
INS_HNTC2_MODE,1
INS_HNTC2_REF,1
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,19.8
MOT_PWM_TYPE,6
MOT_THST_EXPO,0.62
MOT_THST_HOVER,0.12
PILOT_Y_EXPO,0.4
PILOT_Y_RATE,600
PSC_ACCZ_I,0.24
PSC_ACCZ_P,0.12
SCHED_LOOP_RATE,800
SERVO_BLH_AUTO,1
SERVO_BLH_BDMASK,15
SERVO_BLH_RVMASK,6
SERVO_BLH_TRATE,5
SERVO_DSHOT_ESC,1
SERVO_DSHOT_RATE,2
#NOTE: iFlight Chimera7 params for ArduPilot Copter 4.2
ACRO_RP_EXPO,0.6
ACRO_RP_RATE,600
ACRO_Y_EXPO,0.6
ACRO_Y_RATE,600
ATC_ACCEL_P_MAX,281062.5
ATC_ACCEL_R_MAX,301679.8
ATC_ACCEL_Y_MAX,72000
ATC_ANG_PIT_P,18
ATC_ANG_RLL_P,18
ATC_ANG_YAW_P,11
ATC_RAT_PIT_D,0.001879093
ATC_RAT_PIT_FLTD,60
ATC_RAT_PIT_FLTT,30
ATC_RAT_PIT_I,0.09663188
ATC_RAT_PIT_P,0.09663188
ATC_RAT_RLL_D,0.001453624
ATC_RAT_RLL_FLTD,75
ATC_RAT_RLL_FLTT,30
ATC_RAT_RLL_I,0.07706726
ATC_RAT_RLL_P,0.07706726
ATC_RAT_YAW_D,0.02
ATC_RAT_YAW_FF,0.0043
ATC_RAT_YAW_FLTD,60
ATC_RAT_YAW_FLTE,1.887445
ATC_RAT_YAW_FLTT,30
ATC_RAT_YAW_I,0.01927038
ATC_RAT_YAW_P,0.1927038
BATT_AMP_OFFSET,-0.04308
BATT_AMP_PERVLT,52.706
BATT_CURR_PIN,11
BATT_LOW_VOLT,21.6
BATT_MONITOR,4
COMPASS_AUTO_ROT,0
COMPASS_CUS_PIT,-15
COMPASS_CUS_ROLL,0
COMPASS_CUS_YAW,180
COMPASS_ORIENT,100
EK3_PRIMARY,1
EK3_IMU_MASK,2
FRAME_CLASS,1
FRAME_TYPE,12
INS_GYRO_FILTER,150
INS_HNTCH_BW,20
INS_HNTCH_ENABLE,1
INS_HNTCH_FREQ,40
INS_HNTCH_HMNCS,1
INS_HNTCH_MODE,3
INS_HNTCH_OPTS,6
INS_HNTCH_REF,1
INS_HNTC2_BW,75
INS_HNTC2_ENABLE,1
INS_HNTC2_FREQ,150
INS_HNTC2_HMNCS,1
INS_HNTC2_MODE,1
INS_HNTC2_REF,1
MOT_BAT_VOLT_MAX,25.2
MOT_BAT_VOLT_MIN,19.8
MOT_PWM_TYPE,6
MOT_THST_EXPO,0.62
MOT_THST_HOVER,0.12
PILOT_Y_EXPO,0.4
PILOT_Y_RATE,600
PSC_ACCZ_I,0.24
PSC_ACCZ_P,0.12
SCHED_LOOP_RATE,800
SERVO_BLH_AUTO,1
SERVO_BLH_BDMASK,15
SERVO_BLH_RVMASK,6
SERVO_BLH_TRATE,5
SERVO_DSHOT_ESC,1
SERVO_DSHOT_RATE,2

BIN
Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin generated

Binary file not shown.

BIN
Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin generated

Binary file not shown.

BIN
Tools/IO_Firmware/iofirmware_highpolh.bin generated

Binary file not shown.

BIN
Tools/IO_Firmware/iofirmware_lowpolh.bin generated

Binary file not shown.

18
Tools/Linux_HAL_Essentials/pru/rangefinderpru/HexUtil_PRU.cmd

@ -1,9 +1,9 @@ @@ -1,9 +1,9 @@
-b
--image
ROMS {
PAGE 0:
.text: o = 0x0, l = 0x2000, files={rangefinderprutext.bin}
PAGE 1:
.data: o = 0x0, l = 0x2000, files={rangefinderprudata.bin}
}
-b
--image
ROMS {
PAGE 0:
.text: o = 0x0, l = 0x2000, files={rangefinderprutext.bin}
PAGE 1:
.data: o = 0x0, l = 0x2000, files={rangefinderprudata.bin}
}

BIN
Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprudata.bin generated

Binary file not shown.

BIN
Tools/Linux_HAL_Essentials/pru/rangefinderpru/rangefinderprutext.bin generated

Binary file not shown.

15554
Tools/LogAnalyzer/examples/mechanical_fail.log

File diff suppressed because it is too large Load Diff

9500
Tools/LogAnalyzer/examples/robert_lefebvre_octo_PM.log

File diff suppressed because it is too large Load Diff

8394
Tools/LogAnalyzer/examples/tradheli_brownout.log

File diff suppressed because it is too large Load Diff

4
Tools/ardupilotwaf/boards.py

@ -278,7 +278,7 @@ class Board: @@ -278,7 +278,7 @@ class Board:
'-Werror=unused-value',
'-Werror=unused-variable',
'-Werror=delete-non-virtual-dtor',
'-Wfatal-errors',
# '-Wfatal-errors',
'-Wno-trigraphs',
'-Werror=parentheses',
'-DARDUPILOT_BUILD',
@ -834,7 +834,7 @@ class chibios(Board): @@ -834,7 +834,7 @@ class chibios(Board):
'-Wmissing-declarations',
'-Wno-unused-parameter',
'-Werror=array-bounds',
'-Wfatal-errors',
# '-Wfatal-errors',
'-Werror=uninitialized',
'-Werror=init-self',
'-Werror=unused-but-set-variable',

12
Tools/autotest/ArduCopter_Tests/copter_terrain_mission.txt

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
QGC WPL 110
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 985.000000 1
1 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 25.000000 1
2 0 10 16 0.000000 0.000000 0.000000 0.000000 36.319240 138.649993 25.000000 1
3 0 10 16 0.000000 0.000000 0.000000 0.000000 36.320035 138.660250 25.000000 1
4 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
QGC WPL 110
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 985.000000 1
1 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 25.000000 1
2 0 10 16 0.000000 0.000000 0.000000 0.000000 36.319240 138.649993 25.000000 1
3 0 10 16 0.000000 0.000000 0.000000 0.000000 36.320035 138.660250 25.000000 1
4 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1

12
Tools/autotest/ArduRover_Tests/DepthFinder/rover1.txt

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
QGC WPL 110
0 1 0 16 0 0 0 0 40.071377 -105.229790 1583.700000 1
1 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07203730 -105.22771600 50.000000 1
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07168840 -105.22739950 50.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07163090 -105.22847240 50.000000 1
4 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07118340 -105.22971150 50.000000 1
QGC WPL 110
0 1 0 16 0 0 0 0 40.071377 -105.229790 1583.700000 1
1 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07203730 -105.22771600 50.000000 1
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07168840 -105.22739950 50.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07163090 -105.22847240 50.000000 1
4 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 40.07118340 -105.22971150 50.000000 1

44
Tools/autotest/Generic_Missions/CMAC-copter-navtest.txt

@ -1,22 +1,22 @@ @@ -1,22 +1,22 @@
QGC WPL 110
0 1 0 16 0 0 0 0 -35.363264 149.165235 584.080017 1
1 0 3 22 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 30.000000 1
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36213670 149.16523670 30.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36213670 149.16439980 30.000000 1
4 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36237510 149.16477800 30.000000 1
5 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36250840 149.16439980 30.000000 1
6 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267920 149.16477800 30.000000 1
7 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36328290 149.16439980 30.000000 1
8 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36383630 149.16487460 30.000000 1
9 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36294370 149.16487460 30.000000 1
10 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36281910 149.16487460 30.000000 1
11 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267700 149.16487460 30.000000 1
12 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267700 149.16497700 30.000000 1
13 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36261240 149.16497700 30.000000 1
14 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36261240 149.16487460 30.000000 1
15 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36209730 149.16487460 30.000000 1
16 0 3 82 0.00000000 0.00000000 0.00000000 0.00000000 -35.36209730 149.16509990 30.000000 1
17 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36260690 149.16509990 30.000000 1
18 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36326320 149.16509990 30.000000 1
19 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36326320 149.16523930 30.000000 1
20 0 3 21 0.00000000 0.00000000 0.00000000 1.00000000 0.00000000 0.00000000 0.000000 1
QGC WPL 110
0 1 0 16 0 0 0 0 -35.363264 149.165235 584.080017 1
1 0 3 22 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 30.000000 1
2 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36213670 149.16523670 30.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36213670 149.16439980 30.000000 1
4 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36237510 149.16477800 30.000000 1
5 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36250840 149.16439980 30.000000 1
6 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267920 149.16477800 30.000000 1
7 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36328290 149.16439980 30.000000 1
8 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36383630 149.16487460 30.000000 1
9 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36294370 149.16487460 30.000000 1
10 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36281910 149.16487460 30.000000 1
11 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267700 149.16487460 30.000000 1
12 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36267700 149.16497700 30.000000 1
13 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36261240 149.16497700 30.000000 1
14 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36261240 149.16487460 30.000000 1
15 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36209730 149.16487460 30.000000 1
16 0 3 82 0.00000000 0.00000000 0.00000000 0.00000000 -35.36209730 149.16509990 30.000000 1
17 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36260690 149.16509990 30.000000 1
18 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36326320 149.16509990 30.000000 1
19 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36326320 149.16523930 30.000000 1
20 0 3 21 0.00000000 0.00000000 0.00000000 1.00000000 0.00000000 0.00000000 0.000000 1

16
Tools/autotest/XPlane/Soaring in Seattle.waypoints

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
QGC WPL 110
0 1 0 16 0 0 0 0 47.537849 -122.307327 4.510000 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 47.471271 -122.358856 10000.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 47.510940 -122.347870 10000.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 47.494937 -122.301521 10000.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 47.457809 -122.206764 10000.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 47.391609 -122.236633 10000.000000 1
6 0 3 17 0.000000 0.000000 0.000000 0.000000 47.407644 -122.323837 10000.000000 1
QGC WPL 110
0 1 0 16 0 0 0 0 47.537849 -122.307327 4.510000 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 47.471271 -122.358856 10000.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 47.510940 -122.347870 10000.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 47.494937 -122.301521 10000.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 47.457809 -122.206764 10000.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 47.391609 -122.236633 10000.000000 1
6 0 3 17 0.000000 0.000000 0.000000 0.000000 47.407644 -122.323837 10000.000000 1

50
Tools/autotest/fg_plane_view.bat

@ -1,25 +1,25 @@ @@ -1,25 +1,25 @@
set AUTOTESTDIR="%~dp0\aircraft"
FOR /F "delims=" %%D in ('dir /b "\Program Files"\FlightGear*') DO set FGDIR=%%D
echo "Using FlightGear %FGDIR%"
cd "\Program Files\%FGDIR%\bin"
fgfs ^
--native-fdm=socket,in,10,,5503,udp ^
--fdm=external ^
--aircraft=Rascal110-JSBSim ^
--fg-aircraft=%AUTOTESTDIR% ^
--airport=KSFO ^
--geometry=650x550 ^
--bpp=32 ^
--disable-hud-3d ^
--disable-horizon-effect ^
--timeofday=noon ^
--disable-sound ^
--disable-fullscreen ^
--disable-random-objects ^
--disable-ai-models ^
--fog-disable ^
--disable-specular-highlight ^
--disable-anti-alias-hud ^
--wind=0@0
pause
set AUTOTESTDIR="%~dp0\aircraft"
FOR /F "delims=" %%D in ('dir /b "\Program Files"\FlightGear*') DO set FGDIR=%%D
echo "Using FlightGear %FGDIR%"
cd "\Program Files\%FGDIR%\bin"
fgfs ^
--native-fdm=socket,in,10,,5503,udp ^
--fdm=external ^
--aircraft=Rascal110-JSBSim ^
--fg-aircraft=%AUTOTESTDIR% ^
--airport=KSFO ^
--geometry=650x550 ^
--bpp=32 ^
--disable-hud-3d ^
--disable-horizon-effect ^
--timeofday=noon ^
--disable-sound ^
--disable-fullscreen ^
--disable-random-objects ^
--disable-ai-models ^
--fog-disable ^
--disable-specular-highlight ^
--disable-anti-alias-hud ^
--wind=0@0
pause

52
Tools/autotest/fg_quad_view.bat

@ -1,26 +1,26 @@ @@ -1,26 +1,26 @@
set AUTOTESTDIR="%~dp0\aircraft"
c:
FOR /F "delims=" %%D in ('dir /b "\Program Files"\FlightGear*') DO set FGDIR=%%D
echo "Using FlightGear %FGDIR%"
cd "\Program Files\%FGDIR%\bin"
fgfs ^
--native-fdm=socket,in,10,,5503,udp ^
--fdm=external ^
--aircraft=arducopter ^
--fg-aircraft=%AUTOTESTDIR% ^
--airport=KSFO ^
--geometry=650x550 ^
--bpp=32 ^
--disable-hud-3d ^
--disable-horizon-effect ^
--timeofday=noon ^
--disable-sound ^
--disable-fullscreen ^
--disable-random-objects ^
--disable-ai-models ^
--fog-disable ^
--disable-specular-highlight ^
--disable-anti-alias-hud ^
--wind=0@0
pause
set AUTOTESTDIR="%~dp0\aircraft"
c:
FOR /F "delims=" %%D in ('dir /b "\Program Files"\FlightGear*') DO set FGDIR=%%D
echo "Using FlightGear %FGDIR%"
cd "\Program Files\%FGDIR%\bin"
fgfs ^
--native-fdm=socket,in,10,,5503,udp ^
--fdm=external ^
--aircraft=arducopter ^
--fg-aircraft=%AUTOTESTDIR% ^
--airport=KSFO ^
--geometry=650x550 ^
--bpp=32 ^
--disable-hud-3d ^
--disable-horizon-effect ^
--timeofday=noon ^
--disable-sound ^
--disable-fullscreen ^
--disable-random-objects ^
--disable-ai-models ^
--fog-disable ^
--disable-specular-highlight ^
--disable-anti-alias-hud ^
--wind=0@0
pause

1
Tools/autotest/locations.txt

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
#NAME=latitude,longitude,absolute-altitude,heading
CYDS=24.6187612,118.0383748,0,0
OSRF0=37.4003371,-122.0800351,0,353
OSRF0_PILOTSBOX=37.4003371,-122.0800351,2,270
CMAC=-35.363261,149.165230,584,353

120
Tools/autotest/models/Callisto.param

@ -1,60 +1,60 @@ @@ -1,60 +1,60 @@
ACRO_Y_RATE,90
ATC_ACCEL_P_MAX,30000
ATC_ACCEL_R_MAX,30000
ATC_ACCEL_Y_MAX,6000
ATC_ANG_PIT_P,8
ATC_ANG_RLL_P,8
ATC_ANG_YAW_P,5
ATC_INPUT_TC,0.25
ATC_RAT_PIT_D,0.00375
ATC_RAT_PIT_FLTD,10
ATC_RAT_PIT_I,0.455
ATC_RAT_PIT_P,0.455
ATC_RAT_RLL_D,0.00375
ATC_RAT_RLL_FLTD,10
ATC_RAT_RLL_I,0.455
ATC_RAT_RLL_P,0.455
ATC_RAT_YAW_FLTE,10
ATC_RAT_YAW_I,0.05
ATC_RAT_YAW_P,0.5
ATC_SLEW_YAW,3000
ATC_THR_MIX_MAX,2
EK3_DRAG_BCOEF_X,91.2220
EK3_DRAG_BCOEF_Y,91.2220
EK3_DRAG_MCOEF,0.0760
FOLL_ALT_TYPE,1
FOLL_DIST_MAX,10000
FOLL_ENABLE,1
FOLL_OFS_TYPE,1
FRAME_CLASS,4
FRAME_TYPE,1
INS_ACCEL_FILTER,10
LOIT_ANG_MAX,25
MOT_BAT_CURR_TC,2
MOT_BAT_VOLT_MAX,50.4
MOT_BAT_VOLT_MIN,39.6
MOT_HOVER_LEARN,0
MOT_PWM_MAX,1940
MOT_PWM_MIN,1000
MOT_SPIN_ARM,0.16
MOT_SPIN_MAX,0.975
MOT_SPIN_MIN,0.2
MOT_THST_EXPO,0.5
MOT_THST_HOVER,0.52
MOT_YAW_HEADROOM,50
PILOT_THR_BHV,3
PILOT_Y_RATE,60
PSC_ACCZ_FLTD,10
PSC_ACCZ_FLTE,0
PSC_ACCZ_FLTT,10
PSC_ACCZ_I,1.0
PSC_ANGLE_MAX,45
PSC_JERK_Z,10
PSC_POSZ_P,0.5
PSC_VELZ_P,2.5
WP_YAW_BEHAVIOR,1
WPNAV_RFND_USE,0
WPNAV_SPEED,1500
SIM_BATT_VOLTAGE 50
ACRO_Y_RATE,90
ATC_ACCEL_P_MAX,30000
ATC_ACCEL_R_MAX,30000
ATC_ACCEL_Y_MAX,6000
ATC_ANG_PIT_P,8
ATC_ANG_RLL_P,8
ATC_ANG_YAW_P,5
ATC_INPUT_TC,0.25
ATC_RAT_PIT_D,0.00375
ATC_RAT_PIT_FLTD,10
ATC_RAT_PIT_I,0.455
ATC_RAT_PIT_P,0.455
ATC_RAT_RLL_D,0.00375
ATC_RAT_RLL_FLTD,10
ATC_RAT_RLL_I,0.455
ATC_RAT_RLL_P,0.455
ATC_RAT_YAW_FLTE,10
ATC_RAT_YAW_I,0.05
ATC_RAT_YAW_P,0.5
ATC_SLEW_YAW,3000
ATC_THR_MIX_MAX,2
EK3_DRAG_BCOEF_X,91.2220
EK3_DRAG_BCOEF_Y,91.2220
EK3_DRAG_MCOEF,0.0760
FOLL_ALT_TYPE,1
FOLL_DIST_MAX,10000
FOLL_ENABLE,1
FOLL_OFS_TYPE,1
FRAME_CLASS,4
FRAME_TYPE,1
INS_ACCEL_FILTER,10
LOIT_ANG_MAX,25
MOT_BAT_CURR_TC,2
MOT_BAT_VOLT_MAX,50.4
MOT_BAT_VOLT_MIN,39.6
MOT_HOVER_LEARN,0
MOT_PWM_MAX,1940
MOT_PWM_MIN,1000
MOT_SPIN_ARM,0.16
MOT_SPIN_MAX,0.975
MOT_SPIN_MIN,0.2
MOT_THST_EXPO,0.5
MOT_THST_HOVER,0.52
MOT_YAW_HEADROOM,50
PILOT_THR_BHV,3
PILOT_Y_RATE,60
PSC_ACCZ_FLTD,10
PSC_ACCZ_FLTE,0
PSC_ACCZ_FLTT,10
PSC_ACCZ_I,1.0
PSC_ANGLE_MAX,45
PSC_JERK_Z,10
PSC_POSZ_P,0.5
PSC_VELZ_P,2.5
WP_YAW_BEHAVIOR,1
WPNAV_RFND_USE,0
WPNAV_SPEED,1500
SIM_BATT_VOLTAGE 50

357
Tools/autotest/web-firmware/Tools/FilterTool/index.html

@ -1,357 +0,0 @@ @@ -1,357 +0,0 @@
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="utf-8" />
<title>ArduPilot Filter Analysis</title>
<script type="text/javascript" src="filters.js"></script>
<script type="text/javascript" src="FileSaver.js"></script>
<script type="text/javascript" src={{url_for('static', filename='filters.js')}}></script>
<script type="text/javascript" src={{url_for('static', filename='FileSaver.js')}}></script>
<script src="https://cdnjs.cloudflare.com/ajax/libs/Chart.js/2.9.4/Chart.js"></script>
<script src="https://www.lactame.com/lib/ml/6.0.0/ml.min.js"></script>
</head>
<a href="https://ardupilot.org"><img src="logo.png"></a>
<h1>ArduPilot Filter Analysis</h1>
The following form will display the attenuation and phase lag for an
ArduPilot 4.2 filter setup.
<body onload="load_cookies(); fill_docs(); update_all_hidden(); calculate_filter(); calculate_pid(); ">
<canvas id="Attenuation" style="width:100%;max-width:1200px"></canvas>
<p>
<input type="button" id="calculate" value="Calculate">
<input type="button" id="SaveParams" value="Save Parameters" onclick="save_parameters();">
<button class="styleClass" onclick="document.getElementById('param_file').click()">Load Parameters</button>
<input type='file' id="param_file" style="display:none" onchange="load_parameters(this.files[0]);">
<form id="params" action="">
<fieldset style="max-width:1200px">
<legend>Graph Settings</legend>
<table>
<tr>
<td>
<fieldset style="width:150px">
<legend>Magnitude scale</legend>
<input type="radio" id="ScaleLog" name="Scale" value="Log" checked>
<label for="LogScale">dB</label><br>
<input type="radio" id="ScaleLinear" name="Scale" value="Linear">
<label for="LinearScale">Linear</label><br>
</fieldset>
</td>
<td>
<fieldset style="width:150px">
<legend>Frequency scale</legend>
<table>
<tr>
<td>
<input type="radio" id="freq_ScaleLog" name="feq_scale" value="Log" checked>
<label for="LogScale">Log</label><br>
<input type="radio" id="freq_ScaleLinear" name="feq_scale" value="Linear">
<label for="LinearScale">Linear</label><br>
</td>
<td>
<input type="radio" id="freq_Scale_Hz" name="feq_unit" value="Hz" checked>
<label for="Scale_unit_Hz">Hz</label><br>
<input type="radio" id="freq_Scale_RPM" name="feq_unit" value="RPM">
<label for="Scale_unit_RPM">RPM</label><br>
</td>
</tr>
</table>
</fieldset>
</td>
</tr>
</table>
<p>
<label for="MaxFreq">Maximum Displayed Frequency</label>
<input id="MaxFreq" name="MaxFreq" type="number" step="1" value="150" onchange="check_nyquist();"/>
<label id="MaxFreq_warning"></label>
</p>
<p>
<label for="MaxPhaseLag">Maximum Displayed Phase Lag</label>
<input id="MaxPhaseLag" name="MaxPhaseLag" type="number" step="1" value="360"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>INS Settings</legend>
<p>
<label for="GyroSampleRate">Gyro Sample Rate</label>
<input id="GyroSampleRate" name="GYRO_SAMPLE_RATE" type="number" step="1" value="2000"/>
</p>
<p>
<label for="INS_GYRO_FILTER">INS_GYRO_FILTER</label>
<input id="INS_GYRO_FILTER" name="INS_GYRO_FILTER" type="number" step="0.1" value="20.0"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>First Notch Filter</legend>
<p>
<label for="INS_HNTCH_ENABLE">INS_HNTCH_ENABLE</label>
<input id="INS_HNTCH_ENABLE" name="INS_HNTCH_ENABLE" type="number" step="1" value="0" onchange="update_hidden(this.id); fill_docs();"/>
<label id="INS_HNTCH_ENABLE.doc"></label>
</p>
<p>
<label for="INS_HNTCH_MODE">INS_HNTCH_MODE</label>
<input id="INS_HNTCH_MODE" name="INS_HNTCH_MODE" type="number" step="1" value="0" onchange="update_hidden_mode(); fill_docs();"/>
<label id="INS_HNTCH_MODE.doc"></label>
</p>
<p>
<label for="INS_HNTCH_FREQ">INS_HNTCH_FREQ</label>
<input id="INS_HNTCH_FREQ" name="INS_HNTCH_FREQ" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTCH_BW">INS_HNTCH_BW</label>
<input id="INS_HNTCH_BW" name="INS_HNTCH_BW" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTCH_ATT">INS_HNTCH_ATT</label>
<input id="INS_HNTCH_ATT" name="INS_HNTCH_ATT" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTCH_REF">INS_HNTCH_REF</label>
<input id="INS_HNTCH_REF" name="INS_HNTCH_REF" type="number" step="0.01" value="0"/>
</p>
<p>
<label for="INS_HNTCH_FM_RAT">INS_HNTCH_FM_RAT</label>
<input id="INS_HNTCH_FM_RAT" name="INS_HNTCH_FM_RAT" type="number" step="0.01" value="1.0"/>
</p>
<p>
<label for="INS_HNTCH_HMNCS">INS_HNTCH_HMNCS</label>
<input id="INS_HNTCH_HMNCS" name="INS_HNTCH_HMNCS" type="number" step="1" value="1"/>
<label id="INS_HNTCH_HMNCS.doc"></label>
</p>
<p>
<label for="INS_HNTCH_OPTS">INS_HNTCH_OPTS</label>
<input id="INS_HNTCH_OPTS" name="INS_HNTCH_OPTS" type="number" step="1" value="0"/>
<label id="INS_HNTCH_OPTS.doc"></label>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>Second Notch Filter</legend>
<p>
<label for="INS_HNTC2_ENABLE">INS_HNTC2_ENABLE</label>
<input id="INS_HNTC2_ENABLE" name="INS_HNTC2_ENABLE" type="number" step="1" value="0" onchange="update_hidden(this.id); fill_docs();"/>
<label id="INS_HNTC2_ENABLE.doc"></label>
</p>
<p>
<label for="INS_HNTC2_MODE">INS_HNTC2_MODE</label>
<input id="INS_HNTC2_MODE" name="INS_HNTC2_MODE" type="number" step="1" value="0" onchange="update_hidden_mode(); fill_docs();"/>
<label id="INS_HNTC2_MODE.doc"></label>
</p>
<p>
<label for="INS_HNTC2_FREQ">INS_HNTC2_FREQ</label>
<input id="INS_HNTC2_FREQ" name="INS_HNTC2_FREQ" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTC2_BW">INS_HNTC2_BW</label>
<input id="INS_HNTC2_BW" name="INS_HNTC2_BW" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTC2_ATT">INS_HNTC2_ATT</label>
<input id="INS_HNTC2_ATT" name="INS_HNTC2_ATT" type="number" step="0.1" value="0"/>
</p>
<p>
<label for="INS_HNTC2_REF">INS_HNTC2_REF</label>
<input id="INS_HNTC2_REF" name="INS_HNTC2_REF" type="number" step="0.01" value="0"/>
</p>
<p>
<label for="INS_HNTC2_FM_RAT">INS_HNTC2_FM_RAT</label>
<input id="INS_HNTC2_FM_RAT" name="INS_HNTC2_FM_RAT" type="number" step="0.01" value="1.0"/>
</p>
<p>
<label for="INS_HNTC2_HMNCS">INS_HNTC2_HMNCS</label>
<input id="INS_HNTC2_HMNCS" name="INS_HNTC2_HMNCS" type="number" step="1" value="1"/>
<label id="INS_HNTC2_HMNCS.doc"></label>
</p>
<p>
<label for="INS_HNTC2_OPTS">INS_HNTC2_OPTS</label>
<input id="INS_HNTC2_OPTS" name="INS_HNTC2_OPTS" type="number" step="1" value="0"/>
<label id="INS_HNTC2_OPTS.doc"></label>
</p>
</fieldset>
<fieldset style="max-width:1200px" id="Throttle_input">
<legend>Throttle Based</legend>
<p>
<label for="Throttle">Throttle</label>
<input id="Throttle" name="Throttle" type="number" step="0.01" value="0.3"/>
</p>
</fieldset>
<fieldset style="max-width:1200px" id="ESC_input">
<legend>ESC Telemetry</legend>
<p>
<label for="NUM_MOTORS">Number of Motors</label>
<input id="NUM_MOTORS" name="NUM_MOTORS" type="number" step="1" value="1"/>
</p>
<p>
<label for="ESC_RPM">ESC RPM</label>
<input id="ESC_RPM" name="ESC_RPM" type="number" step="1" value="2500"/>
</p>
</fieldset>
<fieldset style="max-width:1200px" id="RPM_input">
<legend>RPM/EFI Based</legend>
<p>
<label for="RPM1">RPM1</label>
<input id="RPM1" name="RPM1" type="number" step="1" value="2500"/>
</p>
<p>
<label for="RPM2">RPM2</label>
<input id="RPM2" name="RPM2" type="number" step="1" value="2500"/>
</p>
</fieldset>
</form>
<h2>PIDs</h2>
<h3><label id="PID_title">Title</label></h3>
<canvas id="PID_Attenuation" style="width:100%;max-width:1200px"></canvas>
<p>
<input type="button" id="CalculateRoll" value="Caculate Roll" onclick="calculate_pid(this.id);">
<input type="button" id="CalculatePitch" value="Caculate Pitch" onclick="calculate_pid(this.id);">
<input type="button" id="CalculateYaw" value="Caculate Yaw" onclick="calculate_pid(this.id);">
</p>
<form id="PID_params" action="">
<fieldset style="max-width:1200px">
<legend>Graph Settings</legend>
<p>
<table>
<tr>
<td>
<fieldset style="width:150px">
<legend>Gain scale</legend>
<input type="radio" id="PID_ScaleLog" name="PID_Scale" value="Log" checked>
<label for="LogScale">dB</label><br>
<input type="radio" id="PID_ScaleLinear" name="PID_Scale" value="Linear">
<label for="LinearScale">Linear</label><br>
</fieldset>
</td>
<td>
<fieldset style="width:150px">
<legend>Frequency scale</legend>
<table>
<tr>
<td>
<input type="radio" id="PID_freq_ScaleLog" name="PID_feq_scale" value="Log" checked>
<label for="LogScale">Log</label><br>
<input type="radio" id="PID_freq_ScaleLinear" name="PID_feq_scale" value="Linear">
<label for="LinearScale">Linear</label><br>
</td>
<td>
<input type="radio" id="PID_freq_Scale_Hz" name="PID_feq_unit" value="Hz" checked>
<label for="Scale_unit_Hz">Hz</label><br>
<input type="radio" id="PID_freq_Scale_RPM" name="PID_feq_unit" value="RPM">
<label for="Scale_unit_RPM">RPM</label><br>
</td>
</tr>
</table>
</fieldset>
</td>
<td>
<fieldset style="width:150px">
<legend>Filtering</legend>
<input type="radio" id="PID_filtering_Pre" name="filtering" value="Pre" checked>
<label for="LogScale">Pre</label><br>
<input type="radio" id="PID_filtering_Post" name="filtering" value="Post">
<label for="LinearScale">Post</label><br>
</fieldset>
</td>
</tr>
</table>
</p>
<p>
<label for="PID_MaxFreq">Maximum Displayed Frequency</label>
<input id="PID_MaxFreq" name="PID_MaxFreq" type="number" step="1" value="150" onchange="check_nyquist();"/>
<label id="PID_MaxFreq_warning"></label>
</p>
<p>
<label for="PID_MaxPhaseLag">Maximum Displayed Phase Lag</label>
<input id="PID_MaxPhaseLag" name="PID_MaxPhaseLag" type="number" step="1" value="360"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>Loop Rate</legend>
<p>
<label for="SCHED_LOOP_RATE">SCHED_LOOP_RATE</label>
<input id="SCHED_LOOP_RATE" name="SCHED_LOOP_RATE" type="number" step="1" value="400"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>Roll</legend>
<p>
<label for="ATC_RAT_RLL_P">ATC_RAT_RLL_P</label>
<input id="ATC_RAT_RLL_P" name="ATC_RAT_RLL_P" type="number" step="0.01" value="0.135"/>
</p>
<p>
<label for="ATC_RAT_RLL_I">ATC_RAT_RLL_I</label>
<input id="ATC_RAT_RLL_I" name="ATC_RAT_RLL_I" type="number" step="0.01" value="0.135"/>
</p>
<p>
<label for="ATC_RAT_RLL_D">ATC_RAT_RLL_D</label>
<input id="ATC_RAT_RLL_D" name="ATC_RAT_RLL_D" type="number" step="0.0001" value="0.0036"/>
</p>
<p>
<label for="ATC_RAT_RLL_FLTE">ATC_RAT_RLL_FLTE</label>
<input id="ATC_RAT_RLL_FLTE" name="ATC_RAT_RLL_FLTE" type="number" step="0.01" value="0"/>
</p>
<p>
<label for="ATC_RAT_RLL_FLTD">ATC_RAT_RLL_FLTD</label>
<input id="ATC_RAT_RLL_FLTD" name="ATC_RAT_RLL_FLTD" type="number" step="0.01" value="20"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>Pitch</legend>
<p>
<label for="ATC_RAT_PIT_P">ATC_RAT_PIT_P</label>
<input id="ATC_RAT_PIT_P" name="ATC_RAT_PIT_P" type="number" step="0.01" value="0.135"/>
</p>
<p>
<label for="ATC_RAT_PIT_I">ATC_RAT_PIT_I</label>
<input id="ATC_RAT_PIT_I" name="ATC_RAT_PIT_I" type="number" step="0.01" value="0.135"/>
</p>
<p>
<label for="ATC_RAT_PIT_D">ATC_RAT_PIT_D</label>
<input id="ATC_RAT_PIT_D" name="ATC_RAT_PIT_D" type="number" step="0.0001" value="0.0036"/>
</p>
<p>
<label for="ATC_RAT_PIT_FLTE">ATC_RAT_PIT_FLTE</label>
<input id="ATC_RAT_PIT_FLTE" name="ATC_RAT_PIT_FLTE" type="number" step="0.01" value="0"/>
</p>
<p>
<label for="ATC_RAT_PIT_FLTD">ATC_RAT_PIT_FLTD</label>
<input id="ATC_RAT_PIT_FLTD" name="ATC_RAT_PIT_FLTD" type="number" step="0.01" value="20"/>
</p>
</fieldset>
<fieldset style="max-width:1200px">
<legend>Yaw</legend>
<p>
<label for="ATC_RAT_YAW_P">ATC_RAT_YAW_P</label>
<input id="ATC_RAT_YAW_P" name="ATC_RAT_YAW_P" type="number" step="0.01" value="0.09"/>
</p>
<p>
<label for="ATC_RAT_YAW_I">ATC_RAT_YAW_I</label>
<input id="ATC_RAT_YAW_I" name="ATC_RAT_YAW_I" type="number" step="0.01" value="0.009"/>
</p>
<p>
<label for="ATC_RAT_YAW_D">ATC_RAT_YAW_D</label>
<input id="ATC_RAT_YAW_D" name="ATC_RAT_YAW_D" type="number" step="0.0001" value="0"/>
</p>
<p>
<label for="ATC_RAT_YAW_FLTE">ATC_RAT_YAW_FLTE</label>
<input id="ATC_RAT_YAW_FLTE" name="ATC_RAT_YAW_FLTE" type="number" step="0.01" value="2.5"/>
</p>
<p>
<label for="ATC_RAT_YAW_FLTD">ATC_RAT_YAW_FLTD</label>
<input id="ATC_RAT_YAW_FLTD" name="ATC_RAT_YAW_FLTD" type="number" step="0.01" value="0"/>
</p>
</fieldset>
</form>
<script>
var calc_btn = document.getElementById('calculate');
calc_btn.onclick = function() {
calculate_filter();
}
//var clear_btn = document.getElementById('clear_cookies');
//clear_btn.onclick = function() {
// clear_cookies();
//}
</script>
</body>
</html>

160
Tools/autotest/web-firmware/index.html

@ -1,160 +0,0 @@ @@ -1,160 +0,0 @@
<!DOCTYPE HTML>
<html lang="en">
<head>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
<title>ArduPilot Firmware Download</title>
<!--CSS -->
<link href="css/main.css" rel="stylesheet" type="text/css" />
</head>
<body>
<div id="main">
<a href="https://firmware.ardupilot.org/">
<div id="logo">
</div>
</a>
<h2>ArduPilot Firmware builds</h2>
These firmware builds are automatically generated by the
<a href="https://autotest.ardupilot.org">ArduPilot autotest system</a>.<p>
<h2>License</h2>
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
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.<p>
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
GNU General Public License for more details.<p>
For details see <a href="http://www.gnu.org/licenses/gpl.html">http://www.gnu.org/licenses/gpl.html</a>
<h2>Safety</h2>
Operating a powered vehicle of any kind can be a lot of fun. However,
nothing will ruin your day at the park more quickly than an accident
or running afoul of the law. Since we want you to have a great
experience, please make sure that you do all of the following:
<ul>
<li><b>Operate within all local laws and regulations</b>. For
example, in the United States, current regulations require you to
operate most UAVs under 400 foot above ground level, within line of
sight, and away from obstructions and populated areas. Since these
regulations vary from place to place, even within the same country,
ensure that you understand what you need to do to stay compliant.</li>
<li><b>Never operate the vehicle or software in a way that could be
dangerous to you, other people, or property</b>. Propellers, while
rotating, could easily cut you; if a UAV fell on a person or object,
it could cause a lot of pain and damage; a UAV caught in power lines
could cause an outage for many people. As Ben Franklin said, "An
ounce of prevention is worth a pound of cure."</li>
<li><b>Always keep in mind that software and hardware failures
happen</b>. Although we design our products to minimize such issues,
you should always operate with the understanding that a failure could
occur at any point of time and without warning. As such, you should
take the appropriate precautions to minimize danger in case of
failure.</li>
<li><b>Never use the software or hardware for manned vehicles</b>.
The software and hardware we provide is only for use in unmanned
vehicles.</li>
</ul>
<h2>Firmwares</h2>
<a href="Plane"><img src="images/plane.png" width="80"
alt="Plane">Plane</a> - for fixed wing aircraft<p>
<a href="Copter"><img src="images/copter.png" width="80"
alt="Copter">Copter</a> - for multicopters and
traditional helicopters<p>
<a href="Rover"><img src="images/rover.png" width="80"
alt="Rover">Rover</a> - for land vehicles and boats<p>
<a href="Sub"><img src="images/sub.png" width="80"
alt="Sub">Sub</a> - for ROVs and underwater vehicles<p>
<a href="Blimp"><img src="images/blimp.png" width="80"
alt="Blimp">Blimp</a> - for lighter-than-air vehicles<p>
<a href="AntennaTracker"><img src="images/antenna-tracker.png" width="80"
alt="AntennaTracker">Antenna Tracker</a> -
for antenna tracking of ArduPilot vehicles<p>
<a href="Tools/MissionPlanner"><img src="images/planner.png" width="80"
alt="MissionPlanner">MissionPlanner</a> - Mission Planner tool<p>
<a href="Tools/APMPlanner"><img src="images/ap_rc.png" width="80"
alt="APM Planner 2.0">APM Planner 2.0</a> - APM Planner 2.0 tool<p>
<a href="SiK"><img src="images/3DR_Radio.jpg" width="80"
alt="Radio">SiK</a> - SiK Radio Firmware<p>
<a href="Tools"><img src="images/tools.png" width="80"
alt="Tools">Tools</a> - Build and development tools<p>
<a href="devbuild"><img src="images/tools.png" width="80"
alt="Tools">DevBuild</a> - Developer builds<p>
<a href="http://github.com/ArduPilot/companion"><img src="images/companion.png" width="78"
alt="Companion">Companion</a> - Companion Computer example code <a href="Companion">and Images</a></p><p>
<a href="AP_Periph"><img src="images/tools.png" width="80"
alt="AP_Periph">AP_Periph</a> - UAVCAN Peripheral Firmware<p>
<a href="Tools/FilterTool"><img src="images/filter.png" width="80"
alt="FilterTool">FilterTool</a> - Filter Analysis Tool<p>
<h2>Types of firmware available</h2>
To choose a firmware to download you need to choose:
<ul>
<li>The type of board that you have</li>
<li>Whether you want the stable, beta or latest version of the
firmware</li>
</ul>
The meanings of the versions are
<ul>
<li><b>stable</b> - this is the version recommended for new users. It
has had the most testing.</li>
<li><b>beta</b> - this is the firmware to choose if you want to be
part of beta testing of new versions prior to release as a stable
version. Note that during some development times the beta release
will be the same as the stable release.</li>
<li><b>latest</b> - this is the latest version from our <a href="http://github.com/ArduPilot">git source
code repository</a>. This version is only for developers. The code
may have unknown bugs and extreme care should be taken by anyone
using it.</li>
</ul>
For each vehicle type a firmware image is available for each type of
autopilot board supported by that vehicle type.
<h2>Load your firmware using Mission Planner</h2>
<ul>
<li>You can load the <b>stable</b> version of the firmware by selecting the appropriate icon for your airframe from the Firmware Tab.</li>
<li>You can load the <b>beta</b> version of the firmware by selecting the "BETA firmware" button in the bottom right corner of the screen and then the appropriate icon.</li>
<li>You can load the <b>latest</b> version of the firmware by downloading a firmware image from one of the links and selecting the "Load custom firmware" button in
the bottom right corner of the screen.</li>
</ul>
<h2>Loading firmware on Linux or MacOS</h2>
To load a firmware on a Linux or MacOS machine you will need to
use
the <a href="https://raw.github.com/ArduPilot/ardupilot/master/Tools/scripts/uploader.py">uploader.py</a>
python script. You can run it like this:
<pre>
python Tools/scripts/uploader.py --port /dev/ttyACM0 build/Pixracer/bin/arducopter.apj
</pre>
After starting the script, press the reset button on your device to
make it enter bootloader mode.
<h2>Building the firmware yourself</h2>
To build the firmware yourself please see the <a href="https://ardupilot.org/dev/index.html">ArduPilot development site</a>.
</div>
</body>
</html>

64
Tools/autotest/web/index.html

@ -1,64 +0,0 @@ @@ -1,64 +0,0 @@
<!DOCTYPE HTML>
<html lang="en">
<head>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
<title>ArduPilot Automatic Testing</title>
<!--CSS -->
<link rel="stylesheet" href="css/main.css" type="text/css" />
</head>
<body>
<div class="main">
<a href="https://autotest.ardupilot.org/">
<div class="logo">
</div>
</a>
<h2>Automatic test run at ${date}</h2>
<div class="git">Test run on git commit <a href="https://github.com/ArduPilot/ardupilot/commit/${githash}">${githash}</a>
</div>
<h2>Test Results</h2>
<img src="autotest-badge.svg" alt="missing autotest badge"/>
<ul class="testresults">
${{tests:<li>${name} - ${result} (${elapsed} seconds)</li>
}}
</ul>
<h2>Test logs</h2>
<ul class=testlogs>
${{files:<li>${name} - <a href="${fname}">${fname}</a>
}}
</ul>
<h2>Flight Tracks</h2>
<ul class=testlogs>
${{images:${fname}<br><img src="${fname}" alt="${name}" />
}}
</ul>
<h2>Older results</h2>
<div class="git">
Older test results are <a href="history">available here</a>
</div>
</div>
<!-- Global site tag (gtag.js) - Autotest statistics -->
<script async src="https://www.googletagmanager.com/gtag/js?id=UA-75650032-5"></script>
<script>
window.dataLayer = window.dataLayer || [];
function gtag(){dataLayer.push(arguments);}
gtag('js', new Date());
gtag('config', 'UA-75650032-5', { 'anonymize_ip': true });
</script>
</body>
</html>

BIN
Tools/bootloaders/BirdCANdy_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CUAV-Nora_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CUAV-X7_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CUAV_GPS_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CUAVv5Nano_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CUAVv5_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CubeBlack_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CubeOrangePlus_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CubeOrange_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/CubeYellow_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/Durandal_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/F35Lightning_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/F4BY_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/FreeflyRTK_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/Hitec-Airspeed_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/HitecMosaic_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/HolybroG4_GPS_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/HolybroGPS_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/KakuteF4_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/KakuteF7Mini_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/KakuteF7_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/KakuteH7_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MambaF405US-I2C_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MatekF405-STD_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MatekF405-Wing_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MatekF405_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MatekF765-SE_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/MatekF765-Wing_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/Nucleo-G491_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/NucleoH743_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/OMNIBUSF7V2_bl.elf generated

Binary file not shown.

BIN
Tools/bootloaders/OmnibusNanoV6_bl.elf generated

Binary file not shown.

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save