mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Merge branch 'master' into ShadowWalker8642-DMF4
This commit is contained in:
commit
390679f421
2
.github/workflows/test_sitl_blimp.yml
vendored
2
.github/workflows/test_sitl_blimp.yml
vendored
@ -229,7 +229,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
4
.github/workflows/test_sitl_copter.yml
vendored
4
.github/workflows/test_sitl_copter.yml
vendored
@ -247,7 +247,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
@ -343,7 +343,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
2
.github/workflows/test_sitl_plane.yml
vendored
2
.github/workflows/test_sitl_plane.yml
vendored
@ -230,7 +230,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
2
.github/workflows/test_sitl_rover.yml
vendored
2
.github/workflows/test_sitl_rover.yml
vendored
@ -244,7 +244,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
2
.github/workflows/test_sitl_sub.yml
vendored
2
.github/workflows/test_sitl_sub.yml
vendored
@ -244,7 +244,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
2
.github/workflows/test_sitl_tracker.yml
vendored
2
.github/workflows/test_sitl_tracker.yml
vendored
@ -230,7 +230,7 @@ jobs:
|
||||
NOW=$(date -u +"%F-%T")
|
||||
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
|
||||
- name: ccache cache files
|
||||
uses: actions/cache/restore@v3
|
||||
uses: actions/cache/restore@v4
|
||||
with:
|
||||
path: ~/.ccache
|
||||
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
|
||||
|
@ -276,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
};
|
||||
@ -315,7 +321,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
MSG_BATTERY_STATUS,
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
|
||||
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||
@ -643,3 +650,43 @@ void GCS_MAVLINK_Tracker::send_global_position_int()
|
||||
0, // Z speed cm/s (+ve Down)
|
||||
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
|
||||
}
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const
|
||||
{
|
||||
const Mode* modes[] {
|
||||
&tracker.mode_manual,
|
||||
&tracker.mode_stop,
|
||||
&tracker.mode_scan,
|
||||
&tracker.mode_guided,
|
||||
&tracker.mode_servotest,
|
||||
&tracker.mode_auto,
|
||||
&tracker.mode_initialising,
|
||||
};
|
||||
|
||||
const uint8_t mode_count = ARRAY_SIZE(modes);
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name = modes[index_zero]->name();
|
||||
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -30,6 +30,10 @@ protected:
|
||||
void send_nav_controller_output() const override;
|
||||
void send_pid_tuning() override;
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
||||
|
@ -1,5 +1,429 @@
|
||||
Antenna Tracker Release Notes:
|
||||
------------------------------------------------------------------
|
||||
Release 4.6.0-beta 13 Nov 2024
|
||||
|
||||
Changes from 4.5.7
|
||||
|
||||
1) Board specific changes
|
||||
|
||||
- AnyLeaf H7 supports compass and onboard logging
|
||||
- Blitz743Pro supports CAN
|
||||
- BlueRobotics Navigator supports BMP390 baro
|
||||
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
|
||||
- CB Unmanned Stamp H743 support
|
||||
- ClearSky CSKY405 support
|
||||
- CUAV-7-Nano default batt monitor fixed
|
||||
- CubeRed bootloader fixes including disabling 2nd core by default
|
||||
- CubeRed supports PPP networking between primary and secondary MCU
|
||||
- CubeRedPrimary supports external compasses
|
||||
- ESP32 main loop rate improvements
|
||||
- ESP32 RC input fixes and wifi connection reliability improved
|
||||
- ESP32 safety switch and GPIO pin support
|
||||
- FlyingMoon no longer support MAX7456
|
||||
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
|
||||
- Flywoo H743 Pro support
|
||||
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
|
||||
- FlywooF745 supports DPS310 baro
|
||||
- FPV boards lose SMBus battery support (to save flash)
|
||||
- GEPRC F745BTHD support
|
||||
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
|
||||
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
|
||||
- Holybro Kakute F4 Wing support
|
||||
- iFlight 2RAW H743 supports onboard logging
|
||||
- JFB110 supports measuring servo rail voltage
|
||||
- JFB110 supports safety switch LED
|
||||
- JHEM-JHEF405 bootloader supports firmware updates via serial
|
||||
- JHEMCU GF30H743 HD support
|
||||
- JHEMCU-GF16-F405 autopilot support
|
||||
- JHEMCU-GSF405A becomes FPV board (to save flash)
|
||||
- KakuteF7 only supports BMP280 baro (to save flash)
|
||||
- KakuteH7Mini supports ICM42688 IMU
|
||||
- Linux auto detection of GPS baud rate fixed
|
||||
- Linux board scheduler jitter reduced
|
||||
- Linux board shutdown fixes
|
||||
- MakeFlyEasy PixPilot-V6Pro support
|
||||
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
|
||||
- MatekH7A3 support Bi-directional DShot
|
||||
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
|
||||
- MicoAir743 internal compass orientation fixed
|
||||
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
|
||||
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
|
||||
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
|
||||
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
|
||||
- mRo Control Zero Classic supports servo rail analog input
|
||||
- mRo KitCAN revC fixed
|
||||
- Mugin MUPilot support
|
||||
- OmnibusF7v2 loses quadplane support (to save flash)
|
||||
- Pixhack-v3 board added (same as fmuv3)
|
||||
- Pixhawk6C bootloader supports flashing firmware from SD card
|
||||
- RadiolinkPIX6 imu orientation fixed
|
||||
- RadiolinkPIX6 supports SPA06 baro
|
||||
- ReaperF745 V4 FC supports MPU6000 IMU
|
||||
- RPI5 support
|
||||
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
|
||||
- Solo serial ports default to MAVLink1
|
||||
- SpeedyBeeF405Wing gets Bi-directional DShot
|
||||
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
|
||||
- Spektreworks boom board support
|
||||
- TrueNavPro-G4 SPI does not share DMA
|
||||
- X-MAV AP-H743v2 support
|
||||
|
||||
2) AHRS/EKF enhancements and fixes
|
||||
|
||||
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
|
||||
- AHRS_OPTION to disable innovation check for airspeed sensor
|
||||
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
|
||||
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
|
||||
- EK2 supports disabling external nav (see EK2_OPTIONS)
|
||||
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
|
||||
- EK3 uses filtered velocity corrections for IMU position
|
||||
- EKF2, EKF3, ExternalAHRS all use common origin
|
||||
- EKF3 accepts set origin even when using GPS
|
||||
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
|
||||
- EKF3 copes better with GPS jamming
|
||||
- EKF3 logs mag fusion selection to XKFS
|
||||
- EKF3 wind estimation when using GPS-for-yaw fixed
|
||||
- External AHRS improvements including handling variances, pre-arm origin check
|
||||
- Inertial Labs External AHRS fixes
|
||||
- VectorNav driver fix for handling of error from sensor
|
||||
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
|
||||
- VectorNav support for sensors outside VN-100 and VN-300
|
||||
|
||||
3) Driver enhancements and bug fixes
|
||||
|
||||
- ADSB fix to display last character in status text sent to GCS
|
||||
- Ainstein LR-D1 radar support
|
||||
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
|
||||
- AIRSPEED message sent to GCS
|
||||
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
|
||||
- ARSPD_OPTIONS to report calibration offset to GCS
|
||||
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
|
||||
- Baro provides improved atmospheric model for high altitude flight
|
||||
- BARO_ALT_OFFSET slew slowed to keep EKF happy
|
||||
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
|
||||
- BATTx_OPTION to not send battery voltage, current, etc to GCS
|
||||
- Benewake RDS02U radar support
|
||||
- Bi-directional DShot on IOMCU supports reversible mask
|
||||
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
|
||||
- BMM350 compass support
|
||||
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
|
||||
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
|
||||
- CRSF baro and vertical speeed fixed
|
||||
- CRSF RX bind command support
|
||||
- DroneCAN battery monitor check to avoid memory corruption when type changed
|
||||
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
|
||||
- DroneCAN EFI health check fix
|
||||
- DroneCAN ESC battery monitors calculate consumed mah
|
||||
- DroneCAN ESCs forced to zero when disarmed
|
||||
- DroneCAN RPM message support
|
||||
- DroneCAN timeout fix for auxiliary frames
|
||||
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
|
||||
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
|
||||
- FuelLevel battery monitor fix to report capacity
|
||||
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
|
||||
- Hirth EFI logging includes modified throttle
|
||||
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
|
||||
- Hott and LTM telemetry deprecated (still available through custom build server)
|
||||
- i-BUS telemetry support
|
||||
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
|
||||
- ICE_START_CHAN replaced with RC aux function (Plane only)
|
||||
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
|
||||
- IE 2400 generator error message severity to GCS improved
|
||||
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
|
||||
- MCP9600 temperature sensor I2C address fixed
|
||||
- MLX90614 temperature sensor support
|
||||
- MSP GPS ground course scaling fixed
|
||||
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
|
||||
- Networking supports reconnection to TCP server or client
|
||||
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
|
||||
- Relay inverted output support (see RELAYx_INVERTED parameter)
|
||||
- ROMFS efficiency improvements
|
||||
- RS-485 driver enable RTS flow control
|
||||
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
|
||||
- Septentrio GPS sat count correctly drops to zero when 255 received
|
||||
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
|
||||
- Single LED for user notification supported
|
||||
- SPA06 baro supported
|
||||
- Sum battery monitor optionally reports minimum voltage instead of average
|
||||
- Sum battery monitor reports average temp
|
||||
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
|
||||
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
|
||||
- UBlox GPS time ignored until at least 2D fix
|
||||
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
|
||||
- Volz logs desired and actual position, voltage, current, motor and PCB temp
|
||||
- Volz server feedback and logging fixed
|
||||
- Volz servo output in its own thread resulting in smoother movements
|
||||
- W25N02KV flash support
|
||||
|
||||
4) Networking enhancements and fixes
|
||||
|
||||
- Allow multiple UDP clients to connect/disconnect/reconnect
|
||||
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
|
||||
|
||||
5) Camera and gimbal enhancements
|
||||
|
||||
- Alexmos precision improved slightly
|
||||
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
|
||||
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
|
||||
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
|
||||
- Dual serial camera gimbal mounts fixed
|
||||
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
|
||||
- Retract Mount2 aux function added (see RCx_OPTION = 113)
|
||||
- Servo gimbal reported angles respect roll, pitch and yaw limits
|
||||
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
|
||||
- Siyi picture and video download scripts
|
||||
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
|
||||
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
|
||||
- Siyi ZT6 hardware id and set-lens fixed
|
||||
- Topotek gimbal support
|
||||
- Trigger distance ignores GPS status and only uses EKF reported location
|
||||
|
||||
6) Harmonic notch enhancements
|
||||
|
||||
- Harmonic notch is active in forward flight on quadplanes
|
||||
- Harmonic notch filter freq clamping and disabling reworked
|
||||
- Harmonic notch handles negative ESC RPMs
|
||||
- Harmonic notch supports per-motor throttle-based harmonic notch
|
||||
|
||||
7) Copter specific enhancements and bug fixes
|
||||
|
||||
- Attitude control fix to dt update order (reduces rate controller noise)
|
||||
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
|
||||
- Auto mode small target position jump when takeoff completes removed
|
||||
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
|
||||
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
|
||||
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
|
||||
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
|
||||
- AutoTune fix to prevent spool up after landing
|
||||
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
|
||||
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
|
||||
- Config error avoided if auto mode is paused very soon after poweron
|
||||
- FLIGHT_OPTIONS bit added to require position estimate before arming
|
||||
- Follow mode slowdown calcs fixed when target is moving
|
||||
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
|
||||
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
|
||||
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
|
||||
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
|
||||
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
|
||||
- Landing detector logging added to ease support (see LDET message)
|
||||
- Loiter unlimited command accepts NaNs (QGC sends these)
|
||||
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
|
||||
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
|
||||
- Payload place bug fix when aborted because gripper is already released
|
||||
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
|
||||
- RTL_ALT minimum reduced to 30cm
|
||||
- SystemID position controller support (Copter and Heli)
|
||||
- TriCopter motor test and slew-up fixed
|
||||
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
|
||||
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
|
||||
|
||||
8) TradHeli specific enhancements
|
||||
|
||||
- Autorotation yaw behaviour fix
|
||||
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
|
||||
- Blade pitch angle logging added (see SWSH log message)
|
||||
- Constrain cyclic roll for intermeshing
|
||||
- ICE / turbine cool down fix
|
||||
- Inverted flight extended to non manual throttle modes
|
||||
- Inverted flight transitions smoothed and restricted to only Stabilize mode
|
||||
- SWSH logging fix for reversed collectives
|
||||
|
||||
9) Plane specific enhancements and bug fixes
|
||||
|
||||
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
|
||||
- Allow for different orientations of landing rangefinder
|
||||
- Assistance requirements evaluted on mode change
|
||||
- FBWB/CRUISE climb/sink rate limited by TECS limits
|
||||
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
|
||||
- Glider pullup support (available only through custom build server)
|
||||
- Loiter breakout improved to better handle destinations inside loiter circle
|
||||
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
|
||||
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
|
||||
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
|
||||
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
|
||||
- Quadplane assistance check enhancements
|
||||
- Quadplane Deca frame support
|
||||
- Quadplane gets smoother takeoff by input shaping target accel and velocity
|
||||
- Servo wiggles in altitude wait staged to be one after another
|
||||
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
|
||||
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
|
||||
- Takeoff fixes for fence autoenable
|
||||
- Takeoff improvements including less overshoot of TKOFF_ALT
|
||||
- TECS reset along with other controllers (important if plane dropped from balloon)
|
||||
- Tilt quadplane ramp of motors on back transition fixed
|
||||
- Tiltrotor tilt angles logged
|
||||
- TKOFF_THR_MIN applied to SLT transitions
|
||||
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
|
||||
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
|
||||
|
||||
10) Rover specific enhancements and bug fixes
|
||||
|
||||
- Auto mode reversed state maintained if momentarily switched to Hold mode
|
||||
- Circle mode tracks better and avoids getting stuck at circle edge
|
||||
- Flight time stats fixed
|
||||
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
|
||||
- Omni3Mecanum frame support
|
||||
- Stopping point uses max deceleration (was incorrectly using acceleration)
|
||||
- Wheel rate controller slew rate fix
|
||||
|
||||
11) Antenna Tracker specific enhancements and bug fixes
|
||||
|
||||
- Never track lat,lon of 0,0
|
||||
|
||||
12) Scripting enhancements
|
||||
|
||||
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
|
||||
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
|
||||
- battery_internal_resistance_check.lua monitors battery resistance
|
||||
- CAN:get_device returns nil for unconfigured CAN device
|
||||
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
|
||||
- Copter:get_target_location, update_target_location support
|
||||
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
|
||||
- Display text on OLED display supported
|
||||
- Docs improved for many bindings
|
||||
- EFI get_last_update_ms binding
|
||||
- EFI_SkyPower.lua driver accepts 2nd supply voltage
|
||||
- ESC_slew_rate.lua example script supports testing ESCs
|
||||
- Filesystem CRC32 check to allow scripts to check module versions
|
||||
- forced arming support
|
||||
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
|
||||
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
|
||||
- Halo6000 EFI driver can log all CAN packets for easier debugging
|
||||
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
|
||||
- I2C:transfer support
|
||||
- IMU gyros_consistent and accels_consistent bindings added
|
||||
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
|
||||
- INS bindings for is calibrating, gyro and accel sensor values
|
||||
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
|
||||
- Logging of booleans supported
|
||||
- Lua language checks improved (finds more errors)
|
||||
- MAVLink commands can be called from scripting
|
||||
- MCU voltage binding (see analog:mcu_voltage)
|
||||
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
|
||||
- "open directory failed" false warning when scripts in ROMFS fixed
|
||||
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
|
||||
- Pass by reference values are always initialized
|
||||
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
|
||||
- plane_aerobatics.lua minor enhancements
|
||||
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
|
||||
- "require" function failures in rare circumstances fixed
|
||||
- "require" function works for modules in ROMFS (e.g. not on SD card)
|
||||
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
|
||||
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
|
||||
- SD card formatting supported
|
||||
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
|
||||
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
|
||||
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
|
||||
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
|
||||
- Temperature sensor bindings added
|
||||
- uint64 support
|
||||
- Various performance and memory usage optimizations
|
||||
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
|
||||
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
|
||||
|
||||
13) GCS / mavlink related changes and fixes
|
||||
|
||||
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
|
||||
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
|
||||
- Deny attempts to upload two missions simultaneously
|
||||
- Fence and Rally points may be uploaded using FTP
|
||||
- GPS_INPUT and HIL_GPS handles multiple GPSs
|
||||
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
|
||||
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
|
||||
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
|
||||
- MAV_CMD_SET_HAGL support (Plane only)
|
||||
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
|
||||
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
|
||||
- Message interval supports TERRAIN_REPORT msg
|
||||
- Mission upload may be cancelled using MISSION_CLEAR_ALL
|
||||
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
|
||||
- RC_CHANNELS_RAW deprecated
|
||||
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
|
||||
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
|
||||
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
|
||||
|
||||
14) Logging enhancements and fixes
|
||||
|
||||
- AC_PID resets and I-term sets logged
|
||||
- ANG provides attitude at high rate (equivalent to ATT)
|
||||
- ATT logs angles as floats (better resolution than ints)
|
||||
- CAND message gets driver index
|
||||
- DCM log message includes roll/pitch and yaw error
|
||||
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
|
||||
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
|
||||
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
|
||||
- FMT messages written as required instead of all at beginning
|
||||
- Logging restarted after download completes when LOG_DISARMED = 1
|
||||
- MISE msg logs active mission command (CMD logged when commands are uploaded)
|
||||
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
|
||||
- RPM sensor logging gets instance field, quality and health fields
|
||||
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
|
||||
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
|
||||
- UART data rates logged at 1hz (see UART message)
|
||||
|
||||
15) ROS2 / DDS support
|
||||
|
||||
- Airspeed published
|
||||
- Battery topic reports all available batteries
|
||||
- Compile-time configurable rates for each publisher
|
||||
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
|
||||
- GPS global origin published at 1 Hz
|
||||
- High frequency raw imu data transmission
|
||||
- Joystick support
|
||||
- Support sending waypoints to Copter and Rover
|
||||
- Remove the XML refs file in favor of binary entity creation
|
||||
|
||||
16) Safety related enhancements and fixes
|
||||
|
||||
- Accel/Gyro inconsistent message fixed for using with only single IMU
|
||||
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
|
||||
- Far from EKF origin pre-arm check removed (Copter only)
|
||||
- Fence breach warning message slightly improved
|
||||
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
|
||||
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
|
||||
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
|
||||
- LEDs flash green lights based on EKF location not GPS
|
||||
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
|
||||
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
|
||||
- Pre-arm check if OpenDroneID is compiled in but disabled
|
||||
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
|
||||
- Pre-arm checks alert user more quickly on failure
|
||||
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
|
||||
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
|
||||
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
|
||||
- Warning of duplicate SERIALx_PROTOCOL = RCIN
|
||||
|
||||
17) Other bug fixes and minor enhancements
|
||||
|
||||
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
|
||||
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
|
||||
- Bootloader rejects allocation of broadcast node ID
|
||||
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
|
||||
- Dijkstras fix to correct use of uninitialised variable
|
||||
- DShot rates are not limited by NeoPixel rates
|
||||
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
|
||||
- Filesystem does not show entries for empty @ files
|
||||
- Filesystem efficiency improvements when reading files
|
||||
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
|
||||
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
|
||||
- Internal error thrown if we lose parameters due to saving queue being too small
|
||||
- MAVLink via DroneCAN baud rate fix
|
||||
- SPI pins may also be used as GPIOs
|
||||
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
|
||||
|
||||
18) Developer focused fixes and enhancements
|
||||
|
||||
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
|
||||
- Cygwin build fix for non-SITL builds
|
||||
- Cygwin build fixed with malloc wrap
|
||||
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
|
||||
- EKF3 code generator documentation and cleanup
|
||||
- GPS jamming simulator added
|
||||
- MacOS compiler warnings reduced
|
||||
- SFML joystick support
|
||||
- SITL support for OpenBSD
|
||||
- Text warning if older Fence or Rally point protocols are used
|
||||
------------------------------------------------------------------
|
||||
Release 4.5.7 08 Oct 2024
|
||||
|
||||
Changes from 4.5.7-beta1
|
||||
|
@ -82,7 +82,7 @@ void Tracker::one_second_loop()
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
// update assigned functions and enable auxiliary servos
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// updated armed/disarmed status LEDs
|
||||
update_armed_disarmed();
|
||||
|
@ -22,6 +22,7 @@ public:
|
||||
|
||||
// returns a unique number specific to this mode
|
||||
virtual Mode::Number number() const = 0;
|
||||
virtual const char* name() const = 0;
|
||||
|
||||
virtual bool requires_armed_servos() const = 0;
|
||||
|
||||
@ -41,6 +42,7 @@ protected:
|
||||
class ModeAuto : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::AUTO; }
|
||||
const char* name() const override { return "Auto"; }
|
||||
bool requires_armed_servos() const override { return true; }
|
||||
void update() override;
|
||||
};
|
||||
@ -48,6 +50,7 @@ public:
|
||||
class ModeGuided : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::GUIDED; }
|
||||
const char* name() const override { return "Guided"; }
|
||||
bool requires_armed_servos() const override { return true; }
|
||||
void update() override;
|
||||
|
||||
@ -66,6 +69,7 @@ private:
|
||||
class ModeInitialising : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::INITIALISING; }
|
||||
const char* name() const override { return "Initialising"; }
|
||||
bool requires_armed_servos() const override { return false; }
|
||||
void update() override {};
|
||||
};
|
||||
@ -73,6 +77,7 @@ public:
|
||||
class ModeManual : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::MANUAL; }
|
||||
const char* name() const override { return "Manual"; }
|
||||
bool requires_armed_servos() const override { return true; }
|
||||
void update() override;
|
||||
};
|
||||
@ -80,6 +85,7 @@ public:
|
||||
class ModeScan : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::SCAN; }
|
||||
const char* name() const override { return "Scan"; }
|
||||
bool requires_armed_servos() const override { return true; }
|
||||
void update() override;
|
||||
};
|
||||
@ -87,6 +93,7 @@ public:
|
||||
class ModeServoTest : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::SERVOTEST; }
|
||||
const char* name() const override { return "ServoTest"; }
|
||||
bool requires_armed_servos() const override { return true; }
|
||||
void update() override {};
|
||||
|
||||
@ -96,6 +103,7 @@ public:
|
||||
class ModeStop : public Mode {
|
||||
public:
|
||||
Mode::Number number() const override { return Mode::Number::STOP; }
|
||||
const char* name() const override { return "Stop"; }
|
||||
bool requires_armed_servos() const override { return false; }
|
||||
void update() override {};
|
||||
};
|
||||
|
@ -8,7 +8,7 @@
|
||||
void Tracker::init_servos()
|
||||
{
|
||||
// update assigned functions and enable auxiliary servos
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw);
|
||||
SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch);
|
||||
|
@ -285,13 +285,9 @@ bool Copter::set_target_location(const Location& target_loc)
|
||||
|
||||
return mode_guided.set_destination(target_loc);
|
||||
}
|
||||
#endif //MODE_GUIDED_ENABLED
|
||||
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
// start takeoff to given altitude (for use by scripting)
|
||||
bool Copter::start_takeoff(float alt)
|
||||
bool Copter::start_takeoff(const float alt)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!flightmode->in_guided_mode()) {
|
||||
@ -304,7 +300,11 @@ bool Copter::start_takeoff(float alt)
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif //MODE_GUIDED_ENABLED
|
||||
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
// set target position (for use by scripting)
|
||||
bool Copter::set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt)
|
||||
{
|
||||
@ -727,7 +727,7 @@ void Copter::one_hz_loop()
|
||||
}
|
||||
|
||||
// update assigned functions and enable auxiliary servos
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log terrain data
|
||||
|
@ -668,12 +668,12 @@ private:
|
||||
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
bool start_takeoff(const float alt) override;
|
||||
#endif // MODE_GUIDED_ENABLED
|
||||
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
bool start_takeoff(float alt) override;
|
||||
bool get_target_location(Location& target_loc) override;
|
||||
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
|
||||
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
|
||||
|
@ -505,10 +505,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
@ -583,7 +589,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
#endif
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
static const ap_message STREAM_ADSB_msgs[] = {
|
||||
MSG_ADSB_VEHICLE,
|
||||
@ -1657,3 +1664,120 @@ uint8_t GCS_MAVLINK_Copter::high_latency_wind_direction() const
|
||||
return 0;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Copter::send_available_mode(uint8_t index) const
|
||||
{
|
||||
const Mode* modes[] {
|
||||
#if MODE_AUTO_ENABLED
|
||||
&copter.mode_auto, // This auto is actually auto RTL!
|
||||
&copter.mode_auto, // This one is really is auto!
|
||||
#endif
|
||||
#if MODE_ACRO_ENABLED
|
||||
&copter.mode_acro,
|
||||
#endif
|
||||
&copter.mode_stabilize,
|
||||
&copter.mode_althold,
|
||||
#if MODE_CIRCLE_ENABLED
|
||||
&copter.mode_circle,
|
||||
#endif
|
||||
#if MODE_LOITER_ENABLED
|
||||
&copter.mode_loiter,
|
||||
#endif
|
||||
#if MODE_GUIDED_ENABLED
|
||||
&copter.mode_guided,
|
||||
#endif
|
||||
&copter.mode_land,
|
||||
#if MODE_RTL_ENABLED
|
||||
&copter.mode_rtl,
|
||||
#endif
|
||||
#if MODE_DRIFT_ENABLED
|
||||
&copter.mode_drift,
|
||||
#endif
|
||||
#if MODE_SPORT_ENABLED
|
||||
&copter.mode_sport,
|
||||
#endif
|
||||
#if MODE_FLIP_ENABLED
|
||||
&copter.mode_flip,
|
||||
#endif
|
||||
#if AUTOTUNE_ENABLED
|
||||
&copter.mode_autotune,
|
||||
#endif
|
||||
#if MODE_POSHOLD_ENABLED
|
||||
&copter.mode_poshold,
|
||||
#endif
|
||||
#if MODE_BRAKE_ENABLED
|
||||
&copter.mode_brake,
|
||||
#endif
|
||||
#if MODE_THROW_ENABLED
|
||||
&copter.mode_throw,
|
||||
#endif
|
||||
#if HAL_ADSB_ENABLED
|
||||
&copter.mode_avoid_adsb,
|
||||
#endif
|
||||
#if MODE_GUIDED_NOGPS_ENABLED
|
||||
&copter.mode_guided_nogps,
|
||||
#endif
|
||||
#if MODE_SMARTRTL_ENABLED
|
||||
&copter.mode_smartrtl,
|
||||
#endif
|
||||
#if MODE_FLOWHOLD_ENABLED
|
||||
(Mode*)copter.g2.mode_flowhold_ptr,
|
||||
#endif
|
||||
#if MODE_FOLLOW_ENABLED
|
||||
&copter.mode_follow,
|
||||
#endif
|
||||
#if MODE_ZIGZAG_ENABLED
|
||||
&copter.mode_zigzag,
|
||||
#endif
|
||||
#if MODE_SYSTEMID_ENABLED
|
||||
(Mode *)copter.g2.mode_systemid_ptr,
|
||||
#endif
|
||||
#if MODE_AUTOROTATE_ENABLED
|
||||
&copter.mode_autorotate,
|
||||
#endif
|
||||
#if MODE_TURTLE_ENABLED
|
||||
&copter.mode_turtle,
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t mode_count = ARRAY_SIZE(modes);
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name = modes[index_zero]->name();
|
||||
uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number();
|
||||
|
||||
#if MODE_AUTO_ENABLED
|
||||
// Auto RTL is odd
|
||||
// Have to deal with is separately becase its number and name can change depending on if were in it or not
|
||||
if (index_zero == 0) {
|
||||
mode_number = (uint8_t)Mode::Number::AUTO_RTL;
|
||||
name = "AUTO RTL";
|
||||
|
||||
} else if (index_zero == 1) {
|
||||
mode_number = (uint8_t)Mode::Number::AUTO;
|
||||
name = "AUTO";
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -64,6 +64,10 @@ protected:
|
||||
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
|
||||
#endif
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
// sanity check velocity or acceleration vector components are numbers
|
||||
|
@ -1,5 +1,429 @@
|
||||
ArduPilot Copter Release Notes:
|
||||
------------------------------------------------------------------
|
||||
Release 4.6.0-beta 13 Nov 2024
|
||||
|
||||
Changes from 4.5.7
|
||||
|
||||
1) Board specific changes
|
||||
|
||||
- AnyLeaf H7 supports compass and onboard logging
|
||||
- Blitz743Pro supports CAN
|
||||
- BlueRobotics Navigator supports BMP390 baro
|
||||
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
|
||||
- CB Unmanned Stamp H743 support
|
||||
- ClearSky CSKY405 support
|
||||
- CUAV-7-Nano default batt monitor fixed
|
||||
- CubeRed bootloader fixes including disabling 2nd core by default
|
||||
- CubeRed supports PPP networking between primary and secondary MCU
|
||||
- CubeRedPrimary supports external compasses
|
||||
- ESP32 main loop rate improvements
|
||||
- ESP32 RC input fixes and wifi connection reliability improved
|
||||
- ESP32 safety switch and GPIO pin support
|
||||
- FlyingMoon no longer support MAX7456
|
||||
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
|
||||
- Flywoo H743 Pro support
|
||||
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
|
||||
- FlywooF745 supports DPS310 baro
|
||||
- FPV boards lose SMBus battery support (to save flash)
|
||||
- GEPRC F745BTHD support
|
||||
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
|
||||
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
|
||||
- Holybro Kakute F4 Wing support
|
||||
- iFlight 2RAW H743 supports onboard logging
|
||||
- JFB110 supports measuring servo rail voltage
|
||||
- JFB110 supports safety switch LED
|
||||
- JHEM-JHEF405 bootloader supports firmware updates via serial
|
||||
- JHEMCU GF30H743 HD support
|
||||
- JHEMCU-GF16-F405 autopilot support
|
||||
- JHEMCU-GSF405A becomes FPV board (to save flash)
|
||||
- KakuteF7 only supports BMP280 baro (to save flash)
|
||||
- KakuteH7Mini supports ICM42688 IMU
|
||||
- Linux auto detection of GPS baud rate fixed
|
||||
- Linux board scheduler jitter reduced
|
||||
- Linux board shutdown fixes
|
||||
- MakeFlyEasy PixPilot-V6Pro support
|
||||
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
|
||||
- MatekH7A3 support Bi-directional DShot
|
||||
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
|
||||
- MicoAir743 internal compass orientation fixed
|
||||
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
|
||||
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
|
||||
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
|
||||
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
|
||||
- mRo Control Zero Classic supports servo rail analog input
|
||||
- mRo KitCAN revC fixed
|
||||
- Mugin MUPilot support
|
||||
- OmnibusF7v2 loses quadplane support (to save flash)
|
||||
- Pixhack-v3 board added (same as fmuv3)
|
||||
- Pixhawk6C bootloader supports flashing firmware from SD card
|
||||
- RadiolinkPIX6 imu orientation fixed
|
||||
- RadiolinkPIX6 supports SPA06 baro
|
||||
- ReaperF745 V4 FC supports MPU6000 IMU
|
||||
- RPI5 support
|
||||
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
|
||||
- Solo serial ports default to MAVLink1
|
||||
- SpeedyBeeF405Wing gets Bi-directional DShot
|
||||
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
|
||||
- Spektreworks boom board support
|
||||
- TrueNavPro-G4 SPI does not share DMA
|
||||
- X-MAV AP-H743v2 support
|
||||
|
||||
2) AHRS/EKF enhancements and fixes
|
||||
|
||||
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
|
||||
- AHRS_OPTION to disable innovation check for airspeed sensor
|
||||
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
|
||||
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
|
||||
- EK2 supports disabling external nav (see EK2_OPTIONS)
|
||||
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
|
||||
- EK3 uses filtered velocity corrections for IMU position
|
||||
- EKF2, EKF3, ExternalAHRS all use common origin
|
||||
- EKF3 accepts set origin even when using GPS
|
||||
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
|
||||
- EKF3 copes better with GPS jamming
|
||||
- EKF3 logs mag fusion selection to XKFS
|
||||
- EKF3 wind estimation when using GPS-for-yaw fixed
|
||||
- External AHRS improvements including handling variances, pre-arm origin check
|
||||
- Inertial Labs External AHRS fixes
|
||||
- VectorNav driver fix for handling of error from sensor
|
||||
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
|
||||
- VectorNav support for sensors outside VN-100 and VN-300
|
||||
|
||||
3) Driver enhancements and bug fixes
|
||||
|
||||
- ADSB fix to display last character in status text sent to GCS
|
||||
- Ainstein LR-D1 radar support
|
||||
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
|
||||
- AIRSPEED message sent to GCS
|
||||
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
|
||||
- ARSPD_OPTIONS to report calibration offset to GCS
|
||||
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
|
||||
- Baro provides improved atmospheric model for high altitude flight
|
||||
- BARO_ALT_OFFSET slew slowed to keep EKF happy
|
||||
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
|
||||
- BATTx_OPTION to not send battery voltage, current, etc to GCS
|
||||
- Benewake RDS02U radar support
|
||||
- Bi-directional DShot on IOMCU supports reversible mask
|
||||
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
|
||||
- BMM350 compass support
|
||||
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
|
||||
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
|
||||
- CRSF baro and vertical speeed fixed
|
||||
- CRSF RX bind command support
|
||||
- DroneCAN battery monitor check to avoid memory corruption when type changed
|
||||
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
|
||||
- DroneCAN EFI health check fix
|
||||
- DroneCAN ESC battery monitors calculate consumed mah
|
||||
- DroneCAN ESCs forced to zero when disarmed
|
||||
- DroneCAN RPM message support
|
||||
- DroneCAN timeout fix for auxiliary frames
|
||||
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
|
||||
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
|
||||
- FuelLevel battery monitor fix to report capacity
|
||||
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
|
||||
- Hirth EFI logging includes modified throttle
|
||||
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
|
||||
- Hott and LTM telemetry deprecated (still available through custom build server)
|
||||
- i-BUS telemetry support
|
||||
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
|
||||
- ICE_START_CHAN replaced with RC aux function (Plane only)
|
||||
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
|
||||
- IE 2400 generator error message severity to GCS improved
|
||||
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
|
||||
- MCP9600 temperature sensor I2C address fixed
|
||||
- MLX90614 temperature sensor support
|
||||
- MSP GPS ground course scaling fixed
|
||||
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
|
||||
- Networking supports reconnection to TCP server or client
|
||||
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
|
||||
- Relay inverted output support (see RELAYx_INVERTED parameter)
|
||||
- ROMFS efficiency improvements
|
||||
- RS-485 driver enable RTS flow control
|
||||
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
|
||||
- Septentrio GPS sat count correctly drops to zero when 255 received
|
||||
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
|
||||
- Single LED for user notification supported
|
||||
- SPA06 baro supported
|
||||
- Sum battery monitor optionally reports minimum voltage instead of average
|
||||
- Sum battery monitor reports average temp
|
||||
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
|
||||
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
|
||||
- UBlox GPS time ignored until at least 2D fix
|
||||
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
|
||||
- Volz logs desired and actual position, voltage, current, motor and PCB temp
|
||||
- Volz server feedback and logging fixed
|
||||
- Volz servo output in its own thread resulting in smoother movements
|
||||
- W25N02KV flash support
|
||||
|
||||
4) Networking enhancements and fixes
|
||||
|
||||
- Allow multiple UDP clients to connect/disconnect/reconnect
|
||||
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
|
||||
|
||||
5) Camera and gimbal enhancements
|
||||
|
||||
- Alexmos precision improved slightly
|
||||
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
|
||||
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
|
||||
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
|
||||
- Dual serial camera gimbal mounts fixed
|
||||
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
|
||||
- Retract Mount2 aux function added (see RCx_OPTION = 113)
|
||||
- Servo gimbal reported angles respect roll, pitch and yaw limits
|
||||
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
|
||||
- Siyi picture and video download scripts
|
||||
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
|
||||
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
|
||||
- Siyi ZT6 hardware id and set-lens fixed
|
||||
- Topotek gimbal support
|
||||
- Trigger distance ignores GPS status and only uses EKF reported location
|
||||
|
||||
6) Harmonic notch enhancements
|
||||
|
||||
- Harmonic notch is active in forward flight on quadplanes
|
||||
- Harmonic notch filter freq clamping and disabling reworked
|
||||
- Harmonic notch handles negative ESC RPMs
|
||||
- Harmonic notch supports per-motor throttle-based harmonic notch
|
||||
|
||||
7) Copter specific enhancements and bug fixes
|
||||
|
||||
- Attitude control fix to dt update order (reduces rate controller noise)
|
||||
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
|
||||
- Auto mode small target position jump when takeoff completes removed
|
||||
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
|
||||
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
|
||||
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
|
||||
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
|
||||
- AutoTune fix to prevent spool up after landing
|
||||
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
|
||||
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
|
||||
- Config error avoided if auto mode is paused very soon after poweron
|
||||
- FLIGHT_OPTIONS bit added to require position estimate before arming
|
||||
- Follow mode slowdown calcs fixed when target is moving
|
||||
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
|
||||
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
|
||||
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
|
||||
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
|
||||
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
|
||||
- Landing detector logging added to ease support (see LDET message)
|
||||
- Loiter unlimited command accepts NaNs (QGC sends these)
|
||||
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
|
||||
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
|
||||
- Payload place bug fix when aborted because gripper is already released
|
||||
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
|
||||
- RTL_ALT minimum reduced to 30cm
|
||||
- SystemID position controller support (Copter and Heli)
|
||||
- TriCopter motor test and slew-up fixed
|
||||
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
|
||||
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
|
||||
|
||||
8) TradHeli specific enhancements
|
||||
|
||||
- Autorotation yaw behaviour fix
|
||||
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
|
||||
- Blade pitch angle logging added (see SWSH log message)
|
||||
- Constrain cyclic roll for intermeshing
|
||||
- ICE / turbine cool down fix
|
||||
- Inverted flight extended to non manual throttle modes
|
||||
- Inverted flight transitions smoothed and restricted to only Stabilize mode
|
||||
- SWSH logging fix for reversed collectives
|
||||
|
||||
9) Plane specific enhancements and bug fixes
|
||||
|
||||
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
|
||||
- Allow for different orientations of landing rangefinder
|
||||
- Assistance requirements evaluted on mode change
|
||||
- FBWB/CRUISE climb/sink rate limited by TECS limits
|
||||
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
|
||||
- Glider pullup support (available only through custom build server)
|
||||
- Loiter breakout improved to better handle destinations inside loiter circle
|
||||
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
|
||||
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
|
||||
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
|
||||
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
|
||||
- Quadplane assistance check enhancements
|
||||
- Quadplane Deca frame support
|
||||
- Quadplane gets smoother takeoff by input shaping target accel and velocity
|
||||
- Servo wiggles in altitude wait staged to be one after another
|
||||
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
|
||||
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
|
||||
- Takeoff fixes for fence autoenable
|
||||
- Takeoff improvements including less overshoot of TKOFF_ALT
|
||||
- TECS reset along with other controllers (important if plane dropped from balloon)
|
||||
- Tilt quadplane ramp of motors on back transition fixed
|
||||
- Tiltrotor tilt angles logged
|
||||
- TKOFF_THR_MIN applied to SLT transitions
|
||||
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
|
||||
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
|
||||
|
||||
10) Rover specific enhancements and bug fixes
|
||||
|
||||
- Auto mode reversed state maintained if momentarily switched to Hold mode
|
||||
- Circle mode tracks better and avoids getting stuck at circle edge
|
||||
- Flight time stats fixed
|
||||
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
|
||||
- Omni3Mecanum frame support
|
||||
- Stopping point uses max deceleration (was incorrectly using acceleration)
|
||||
- Wheel rate controller slew rate fix
|
||||
|
||||
11) Antenna Tracker specific enhancements and bug fixes
|
||||
|
||||
- Never track lat,lon of 0,0
|
||||
|
||||
12) Scripting enhancements
|
||||
|
||||
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
|
||||
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
|
||||
- battery_internal_resistance_check.lua monitors battery resistance
|
||||
- CAN:get_device returns nil for unconfigured CAN device
|
||||
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
|
||||
- Copter:get_target_location, update_target_location support
|
||||
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
|
||||
- Display text on OLED display supported
|
||||
- Docs improved for many bindings
|
||||
- EFI get_last_update_ms binding
|
||||
- EFI_SkyPower.lua driver accepts 2nd supply voltage
|
||||
- ESC_slew_rate.lua example script supports testing ESCs
|
||||
- Filesystem CRC32 check to allow scripts to check module versions
|
||||
- forced arming support
|
||||
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
|
||||
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
|
||||
- Halo6000 EFI driver can log all CAN packets for easier debugging
|
||||
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
|
||||
- I2C:transfer support
|
||||
- IMU gyros_consistent and accels_consistent bindings added
|
||||
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
|
||||
- INS bindings for is calibrating, gyro and accel sensor values
|
||||
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
|
||||
- Logging of booleans supported
|
||||
- Lua language checks improved (finds more errors)
|
||||
- MAVLink commands can be called from scripting
|
||||
- MCU voltage binding (see analog:mcu_voltage)
|
||||
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
|
||||
- "open directory failed" false warning when scripts in ROMFS fixed
|
||||
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
|
||||
- Pass by reference values are always initialized
|
||||
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
|
||||
- plane_aerobatics.lua minor enhancements
|
||||
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
|
||||
- "require" function failures in rare circumstances fixed
|
||||
- "require" function works for modules in ROMFS (e.g. not on SD card)
|
||||
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
|
||||
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
|
||||
- SD card formatting supported
|
||||
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
|
||||
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
|
||||
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
|
||||
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
|
||||
- Temperature sensor bindings added
|
||||
- uint64 support
|
||||
- Various performance and memory usage optimizations
|
||||
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
|
||||
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
|
||||
|
||||
13) GCS / mavlink related changes and fixes
|
||||
|
||||
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
|
||||
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
|
||||
- Deny attempts to upload two missions simultaneously
|
||||
- Fence and Rally points may be uploaded using FTP
|
||||
- GPS_INPUT and HIL_GPS handles multiple GPSs
|
||||
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
|
||||
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
|
||||
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
|
||||
- MAV_CMD_SET_HAGL support (Plane only)
|
||||
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
|
||||
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
|
||||
- Message interval supports TERRAIN_REPORT msg
|
||||
- Mission upload may be cancelled using MISSION_CLEAR_ALL
|
||||
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
|
||||
- RC_CHANNELS_RAW deprecated
|
||||
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
|
||||
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
|
||||
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
|
||||
|
||||
14) Logging enhancements and fixes
|
||||
|
||||
- AC_PID resets and I-term sets logged
|
||||
- ANG provides attitude at high rate (equivalent to ATT)
|
||||
- ATT logs angles as floats (better resolution than ints)
|
||||
- CAND message gets driver index
|
||||
- DCM log message includes roll/pitch and yaw error
|
||||
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
|
||||
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
|
||||
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
|
||||
- FMT messages written as required instead of all at beginning
|
||||
- Logging restarted after download completes when LOG_DISARMED = 1
|
||||
- MISE msg logs active mission command (CMD logged when commands are uploaded)
|
||||
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
|
||||
- RPM sensor logging gets instance field, quality and health fields
|
||||
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
|
||||
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
|
||||
- UART data rates logged at 1hz (see UART message)
|
||||
|
||||
15) ROS2 / DDS support
|
||||
|
||||
- Airspeed published
|
||||
- Battery topic reports all available batteries
|
||||
- Compile-time configurable rates for each publisher
|
||||
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
|
||||
- GPS global origin published at 1 Hz
|
||||
- High frequency raw imu data transmission
|
||||
- Joystick support
|
||||
- Support sending waypoints to Copter and Rover
|
||||
- Remove the XML refs file in favor of binary entity creation
|
||||
|
||||
16) Safety related enhancements and fixes
|
||||
|
||||
- Accel/Gyro inconsistent message fixed for using with only single IMU
|
||||
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
|
||||
- Far from EKF origin pre-arm check removed (Copter only)
|
||||
- Fence breach warning message slightly improved
|
||||
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
|
||||
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
|
||||
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
|
||||
- LEDs flash green lights based on EKF location not GPS
|
||||
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
|
||||
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
|
||||
- Pre-arm check if OpenDroneID is compiled in but disabled
|
||||
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
|
||||
- Pre-arm checks alert user more quickly on failure
|
||||
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
|
||||
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
|
||||
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
|
||||
- Warning of duplicate SERIALx_PROTOCOL = RCIN
|
||||
|
||||
17) Other bug fixes and minor enhancements
|
||||
|
||||
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
|
||||
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
|
||||
- Bootloader rejects allocation of broadcast node ID
|
||||
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
|
||||
- Dijkstras fix to correct use of uninitialised variable
|
||||
- DShot rates are not limited by NeoPixel rates
|
||||
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
|
||||
- Filesystem does not show entries for empty @ files
|
||||
- Filesystem efficiency improvements when reading files
|
||||
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
|
||||
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
|
||||
- Internal error thrown if we lose parameters due to saving queue being too small
|
||||
- MAVLink via DroneCAN baud rate fix
|
||||
- SPI pins may also be used as GPIOs
|
||||
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
|
||||
|
||||
18) Developer focused fixes and enhancements
|
||||
|
||||
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
|
||||
- Cygwin build fix for non-SITL builds
|
||||
- Cygwin build fixed with malloc wrap
|
||||
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
|
||||
- EKF3 code generator documentation and cleanup
|
||||
- GPS jamming simulator added
|
||||
- MacOS compiler warnings reduced
|
||||
- SFML joystick support
|
||||
- SITL support for OpenBSD
|
||||
- Text warning if older Fence or Rally point protocols are used
|
||||
------------------------------------------------------------------
|
||||
Release 4.5.7 08 Oct 2024
|
||||
|
||||
Changes from 4.5.7-beta1
|
||||
|
@ -146,9 +146,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||
read_radio();
|
||||
|
||||
// pass through throttle to motors
|
||||
SRV_Channels::cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
|
||||
// read some compass values
|
||||
compass.read();
|
||||
|
@ -95,9 +95,10 @@ void Copter::esc_calibration_passthrough()
|
||||
hal.scheduler->delay(3);
|
||||
|
||||
// pass through to motors
|
||||
SRV_Channels::cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f);
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
}
|
||||
#endif // FRAME_CONFIG != HELI_FRAME
|
||||
}
|
||||
@ -112,25 +113,26 @@ void Copter::esc_calibration_auto()
|
||||
esc_calibration_setup();
|
||||
|
||||
// raise throttle to maximum
|
||||
SRV_Channels::cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
|
||||
// delay for 5 seconds while outputting pulses
|
||||
uint32_t tstart = millis();
|
||||
while (millis() - tstart < 5000) {
|
||||
SRV_Channels::cork();
|
||||
srv.cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(1.0f);
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
esc_calibration_notify();
|
||||
hal.scheduler->delay(3);
|
||||
}
|
||||
|
||||
// block until we restart
|
||||
while(1) {
|
||||
SRV_Channels::cork();
|
||||
srv.cork();
|
||||
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
esc_calibration_notify();
|
||||
hal.scheduler->delay(3);
|
||||
}
|
||||
|
@ -156,8 +156,10 @@ void Copter::motors_output()
|
||||
// output any servo channels
|
||||
SRV_Channels::calc_pwm();
|
||||
|
||||
auto &srv = AP::srv();
|
||||
|
||||
// cork now, so that all channel outputs happen at once
|
||||
SRV_Channels::cork();
|
||||
srv.cork();
|
||||
|
||||
// update output on any aux channels, for manual passthru
|
||||
SRV_Channels::output_ch_all();
|
||||
@ -181,7 +183,7 @@ void Copter::motors_output()
|
||||
}
|
||||
|
||||
// push all channels
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
}
|
||||
|
||||
// check for pilot stick input to trigger lost vehicle alarm
|
||||
|
@ -45,7 +45,7 @@ void Copter::init_rc_out()
|
||||
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
||||
|
||||
// enable aux servos to cope with multiple output channels per motor
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// update rate must be set after motors->init() to allow for motor mapping
|
||||
motors->set_update_rate(g.rc_speed);
|
||||
|
@ -346,7 +346,7 @@ void Plane::one_second_loop()
|
||||
// sync MAVLink system ID
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// update notify flags
|
||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||
|
@ -630,10 +630,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_CURRENT_WAYPOINT,
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
@ -710,7 +716,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
MSG_VIBRATION,
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
static const ap_message STREAM_ADSB_msgs[] = {
|
||||
MSG_ADSB_VEHICLE,
|
||||
@ -1539,3 +1546,99 @@ MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const
|
||||
return MAV_LANDED_STATE_ON_GROUND;
|
||||
}
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Plane::send_available_mode(uint8_t index) const
|
||||
{
|
||||
// Fixed wing modes
|
||||
const Mode* fw_modes[] {
|
||||
&plane.mode_manual,
|
||||
&plane.mode_circle,
|
||||
&plane.mode_stabilize,
|
||||
&plane.mode_training,
|
||||
&plane.mode_acro,
|
||||
&plane.mode_fbwa,
|
||||
&plane.mode_fbwb,
|
||||
&plane.mode_cruise,
|
||||
&plane.mode_autotune,
|
||||
&plane.mode_auto,
|
||||
&plane.mode_rtl,
|
||||
&plane.mode_loiter,
|
||||
#if HAL_ADSB_ENABLED
|
||||
&plane.mode_avoidADSB,
|
||||
#endif
|
||||
&plane.mode_guided,
|
||||
&plane.mode_initializing,
|
||||
&plane.mode_takeoff,
|
||||
#if HAL_SOARING_ENABLED
|
||||
&plane.mode_thermal,
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t fw_mode_count = ARRAY_SIZE(fw_modes);
|
||||
|
||||
// Fixedwing modes are always present
|
||||
uint8_t mode_count = fw_mode_count;
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
// Quadplane modes
|
||||
const Mode* q_modes[] {
|
||||
&plane.mode_qstabilize,
|
||||
&plane.mode_qhover,
|
||||
&plane.mode_qloiter,
|
||||
&plane.mode_qland,
|
||||
&plane.mode_qrtl,
|
||||
&plane.mode_qacro,
|
||||
&plane.mode_loiter_qland,
|
||||
#if QAUTOTUNE_ENABLED
|
||||
&plane.mode_qautotune,
|
||||
#endif
|
||||
};
|
||||
|
||||
// Quadplane modes must be enabled
|
||||
if (plane.quadplane.available()) {
|
||||
mode_count += ARRAY_SIZE(q_modes);
|
||||
}
|
||||
#endif // HAL_QUADPLANE_ENABLED
|
||||
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name;
|
||||
uint8_t mode_number;
|
||||
|
||||
if (index_zero < fw_mode_count) {
|
||||
// A fixedwing mode
|
||||
name = fw_modes[index_zero]->name();
|
||||
mode_number = (uint8_t)fw_modes[index_zero]->mode_number();
|
||||
|
||||
} else {
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
// A Quadplane mode
|
||||
const uint8_t q_index = index_zero - fw_mode_count;
|
||||
name = q_modes[q_index]->name();
|
||||
mode_number = (uint8_t)q_modes[q_index]->mode_number();
|
||||
#else
|
||||
// Should not endup here
|
||||
return mode_count;
|
||||
#endif
|
||||
}
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -50,6 +50,10 @@ protected:
|
||||
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
|
||||
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);
|
||||
|
@ -60,7 +60,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @DisplayName: GCS PID tuning mask
|
||||
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
|
||||
// @User: Advanced
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing
|
||||
// @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing,5:AccZ
|
||||
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
|
||||
|
||||
// @Param: KFF_RDDRMIX
|
||||
@ -158,6 +158,15 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @User: Standard
|
||||
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 0),
|
||||
|
||||
// @Param: TKOFF_THR_IDLE
|
||||
// @DisplayName: Takeoff idle throttle
|
||||
// @Description: The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.
|
||||
// @Units: %
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
ASCALAR(takeoff_throttle_idle, "TKOFF_THR_IDLE", 0),
|
||||
|
||||
// @Param: TKOFF_OPTIONS
|
||||
// @DisplayName: Takeoff options
|
||||
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
|
||||
|
@ -359,6 +359,7 @@ public:
|
||||
k_param_autotune_options,
|
||||
k_param_takeoff_throttle_min,
|
||||
k_param_takeoff_options,
|
||||
k_param_takeoff_throttle_idle,
|
||||
|
||||
k_param_pullup = 270,
|
||||
};
|
||||
|
@ -1159,7 +1159,7 @@ private:
|
||||
void servos_twin_engine_mix();
|
||||
void force_flare();
|
||||
void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle);
|
||||
void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func);
|
||||
void throttle_slew_limit();
|
||||
bool suppress_throttle(void);
|
||||
void update_throttle_hover();
|
||||
void channel_function_mixer(SRV_Channel::Aux_servo_function_t func1_in, SRV_Channel::Aux_servo_function_t func2_in,
|
||||
|
@ -1,5 +1,429 @@
|
||||
ArduPilot Plane Release Notes:
|
||||
------------------------------------------------------------------
|
||||
Release 4.6.0-beta 13 Nov 2024
|
||||
|
||||
Changes from 4.5.7
|
||||
|
||||
1) Board specific changes
|
||||
|
||||
- AnyLeaf H7 supports compass and onboard logging
|
||||
- Blitz743Pro supports CAN
|
||||
- BlueRobotics Navigator supports BMP390 baro
|
||||
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
|
||||
- CB Unmanned Stamp H743 support
|
||||
- ClearSky CSKY405 support
|
||||
- CUAV-7-Nano default batt monitor fixed
|
||||
- CubeRed bootloader fixes including disabling 2nd core by default
|
||||
- CubeRed supports PPP networking between primary and secondary MCU
|
||||
- CubeRedPrimary supports external compasses
|
||||
- ESP32 main loop rate improvements
|
||||
- ESP32 RC input fixes and wifi connection reliability improved
|
||||
- ESP32 safety switch and GPIO pin support
|
||||
- FlyingMoon no longer support MAX7456
|
||||
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
|
||||
- Flywoo H743 Pro support
|
||||
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
|
||||
- FlywooF745 supports DPS310 baro
|
||||
- FPV boards lose SMBus battery support (to save flash)
|
||||
- GEPRC F745BTHD support
|
||||
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
|
||||
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
|
||||
- Holybro Kakute F4 Wing support
|
||||
- iFlight 2RAW H743 supports onboard logging
|
||||
- JFB110 supports measuring servo rail voltage
|
||||
- JFB110 supports safety switch LED
|
||||
- JHEM-JHEF405 bootloader supports firmware updates via serial
|
||||
- JHEMCU GF30H743 HD support
|
||||
- JHEMCU-GF16-F405 autopilot support
|
||||
- JHEMCU-GSF405A becomes FPV board (to save flash)
|
||||
- KakuteF7 only supports BMP280 baro (to save flash)
|
||||
- KakuteH7Mini supports ICM42688 IMU
|
||||
- Linux auto detection of GPS baud rate fixed
|
||||
- Linux board scheduler jitter reduced
|
||||
- Linux board shutdown fixes
|
||||
- MakeFlyEasy PixPilot-V6Pro support
|
||||
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
|
||||
- MatekH7A3 support Bi-directional DShot
|
||||
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
|
||||
- MicoAir743 internal compass orientation fixed
|
||||
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
|
||||
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
|
||||
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
|
||||
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
|
||||
- mRo Control Zero Classic supports servo rail analog input
|
||||
- mRo KitCAN revC fixed
|
||||
- Mugin MUPilot support
|
||||
- OmnibusF7v2 loses quadplane support (to save flash)
|
||||
- Pixhack-v3 board added (same as fmuv3)
|
||||
- Pixhawk6C bootloader supports flashing firmware from SD card
|
||||
- RadiolinkPIX6 imu orientation fixed
|
||||
- RadiolinkPIX6 supports SPA06 baro
|
||||
- ReaperF745 V4 FC supports MPU6000 IMU
|
||||
- RPI5 support
|
||||
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
|
||||
- Solo serial ports default to MAVLink1
|
||||
- SpeedyBeeF405Wing gets Bi-directional DShot
|
||||
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
|
||||
- Spektreworks boom board support
|
||||
- TrueNavPro-G4 SPI does not share DMA
|
||||
- X-MAV AP-H743v2 support
|
||||
|
||||
2) AHRS/EKF enhancements and fixes
|
||||
|
||||
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
|
||||
- AHRS_OPTION to disable innovation check for airspeed sensor
|
||||
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
|
||||
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
|
||||
- EK2 supports disabling external nav (see EK2_OPTIONS)
|
||||
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
|
||||
- EK3 uses filtered velocity corrections for IMU position
|
||||
- EKF2, EKF3, ExternalAHRS all use common origin
|
||||
- EKF3 accepts set origin even when using GPS
|
||||
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
|
||||
- EKF3 copes better with GPS jamming
|
||||
- EKF3 logs mag fusion selection to XKFS
|
||||
- EKF3 wind estimation when using GPS-for-yaw fixed
|
||||
- External AHRS improvements including handling variances, pre-arm origin check
|
||||
- Inertial Labs External AHRS fixes
|
||||
- VectorNav driver fix for handling of error from sensor
|
||||
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
|
||||
- VectorNav support for sensors outside VN-100 and VN-300
|
||||
|
||||
3) Driver enhancements and bug fixes
|
||||
|
||||
- ADSB fix to display last character in status text sent to GCS
|
||||
- Ainstein LR-D1 radar support
|
||||
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
|
||||
- AIRSPEED message sent to GCS
|
||||
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
|
||||
- ARSPD_OPTIONS to report calibration offset to GCS
|
||||
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
|
||||
- Baro provides improved atmospheric model for high altitude flight
|
||||
- BARO_ALT_OFFSET slew slowed to keep EKF happy
|
||||
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
|
||||
- BATTx_OPTION to not send battery voltage, current, etc to GCS
|
||||
- Benewake RDS02U radar support
|
||||
- Bi-directional DShot on IOMCU supports reversible mask
|
||||
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
|
||||
- BMM350 compass support
|
||||
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
|
||||
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
|
||||
- CRSF baro and vertical speeed fixed
|
||||
- CRSF RX bind command support
|
||||
- DroneCAN battery monitor check to avoid memory corruption when type changed
|
||||
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
|
||||
- DroneCAN EFI health check fix
|
||||
- DroneCAN ESC battery monitors calculate consumed mah
|
||||
- DroneCAN ESCs forced to zero when disarmed
|
||||
- DroneCAN RPM message support
|
||||
- DroneCAN timeout fix for auxiliary frames
|
||||
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
|
||||
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
|
||||
- FuelLevel battery monitor fix to report capacity
|
||||
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
|
||||
- Hirth EFI logging includes modified throttle
|
||||
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
|
||||
- Hott and LTM telemetry deprecated (still available through custom build server)
|
||||
- i-BUS telemetry support
|
||||
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
|
||||
- ICE_START_CHAN replaced with RC aux function (Plane only)
|
||||
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
|
||||
- IE 2400 generator error message severity to GCS improved
|
||||
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
|
||||
- MCP9600 temperature sensor I2C address fixed
|
||||
- MLX90614 temperature sensor support
|
||||
- MSP GPS ground course scaling fixed
|
||||
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
|
||||
- Networking supports reconnection to TCP server or client
|
||||
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
|
||||
- Relay inverted output support (see RELAYx_INVERTED parameter)
|
||||
- ROMFS efficiency improvements
|
||||
- RS-485 driver enable RTS flow control
|
||||
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
|
||||
- Septentrio GPS sat count correctly drops to zero when 255 received
|
||||
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
|
||||
- Single LED for user notification supported
|
||||
- SPA06 baro supported
|
||||
- Sum battery monitor optionally reports minimum voltage instead of average
|
||||
- Sum battery monitor reports average temp
|
||||
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
|
||||
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
|
||||
- UBlox GPS time ignored until at least 2D fix
|
||||
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
|
||||
- Volz logs desired and actual position, voltage, current, motor and PCB temp
|
||||
- Volz server feedback and logging fixed
|
||||
- Volz servo output in its own thread resulting in smoother movements
|
||||
- W25N02KV flash support
|
||||
|
||||
4) Networking enhancements and fixes
|
||||
|
||||
- Allow multiple UDP clients to connect/disconnect/reconnect
|
||||
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
|
||||
|
||||
5) Camera and gimbal enhancements
|
||||
|
||||
- Alexmos precision improved slightly
|
||||
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
|
||||
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
|
||||
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
|
||||
- Dual serial camera gimbal mounts fixed
|
||||
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
|
||||
- Retract Mount2 aux function added (see RCx_OPTION = 113)
|
||||
- Servo gimbal reported angles respect roll, pitch and yaw limits
|
||||
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
|
||||
- Siyi picture and video download scripts
|
||||
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
|
||||
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
|
||||
- Siyi ZT6 hardware id and set-lens fixed
|
||||
- Topotek gimbal support
|
||||
- Trigger distance ignores GPS status and only uses EKF reported location
|
||||
|
||||
6) Harmonic notch enhancements
|
||||
|
||||
- Harmonic notch is active in forward flight on quadplanes
|
||||
- Harmonic notch filter freq clamping and disabling reworked
|
||||
- Harmonic notch handles negative ESC RPMs
|
||||
- Harmonic notch supports per-motor throttle-based harmonic notch
|
||||
|
||||
7) Copter specific enhancements and bug fixes
|
||||
|
||||
- Attitude control fix to dt update order (reduces rate controller noise)
|
||||
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
|
||||
- Auto mode small target position jump when takeoff completes removed
|
||||
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
|
||||
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
|
||||
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
|
||||
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
|
||||
- AutoTune fix to prevent spool up after landing
|
||||
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
|
||||
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
|
||||
- Config error avoided if auto mode is paused very soon after poweron
|
||||
- FLIGHT_OPTIONS bit added to require position estimate before arming
|
||||
- Follow mode slowdown calcs fixed when target is moving
|
||||
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
|
||||
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
|
||||
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
|
||||
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
|
||||
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
|
||||
- Landing detector logging added to ease support (see LDET message)
|
||||
- Loiter unlimited command accepts NaNs (QGC sends these)
|
||||
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
|
||||
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
|
||||
- Payload place bug fix when aborted because gripper is already released
|
||||
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
|
||||
- RTL_ALT minimum reduced to 30cm
|
||||
- SystemID position controller support (Copter and Heli)
|
||||
- TriCopter motor test and slew-up fixed
|
||||
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
|
||||
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
|
||||
|
||||
8) TradHeli specific enhancements
|
||||
|
||||
- Autorotation yaw behaviour fix
|
||||
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
|
||||
- Blade pitch angle logging added (see SWSH log message)
|
||||
- Constrain cyclic roll for intermeshing
|
||||
- ICE / turbine cool down fix
|
||||
- Inverted flight extended to non manual throttle modes
|
||||
- Inverted flight transitions smoothed and restricted to only Stabilize mode
|
||||
- SWSH logging fix for reversed collectives
|
||||
|
||||
9) Plane specific enhancements and bug fixes
|
||||
|
||||
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
|
||||
- Allow for different orientations of landing rangefinder
|
||||
- Assistance requirements evaluted on mode change
|
||||
- FBWB/CRUISE climb/sink rate limited by TECS limits
|
||||
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
|
||||
- Glider pullup support (available only through custom build server)
|
||||
- Loiter breakout improved to better handle destinations inside loiter circle
|
||||
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
|
||||
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
|
||||
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
|
||||
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
|
||||
- Quadplane assistance check enhancements
|
||||
- Quadplane Deca frame support
|
||||
- Quadplane gets smoother takeoff by input shaping target accel and velocity
|
||||
- Servo wiggles in altitude wait staged to be one after another
|
||||
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
|
||||
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
|
||||
- Takeoff fixes for fence autoenable
|
||||
- Takeoff improvements including less overshoot of TKOFF_ALT
|
||||
- TECS reset along with other controllers (important if plane dropped from balloon)
|
||||
- Tilt quadplane ramp of motors on back transition fixed
|
||||
- Tiltrotor tilt angles logged
|
||||
- TKOFF_THR_MIN applied to SLT transitions
|
||||
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
|
||||
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
|
||||
|
||||
10) Rover specific enhancements and bug fixes
|
||||
|
||||
- Auto mode reversed state maintained if momentarily switched to Hold mode
|
||||
- Circle mode tracks better and avoids getting stuck at circle edge
|
||||
- Flight time stats fixed
|
||||
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
|
||||
- Omni3Mecanum frame support
|
||||
- Stopping point uses max deceleration (was incorrectly using acceleration)
|
||||
- Wheel rate controller slew rate fix
|
||||
|
||||
11) Antenna Tracker specific enhancements and bug fixes
|
||||
|
||||
- Never track lat,lon of 0,0
|
||||
|
||||
12) Scripting enhancements
|
||||
|
||||
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
|
||||
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
|
||||
- battery_internal_resistance_check.lua monitors battery resistance
|
||||
- CAN:get_device returns nil for unconfigured CAN device
|
||||
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
|
||||
- Copter:get_target_location, update_target_location support
|
||||
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
|
||||
- Display text on OLED display supported
|
||||
- Docs improved for many bindings
|
||||
- EFI get_last_update_ms binding
|
||||
- EFI_SkyPower.lua driver accepts 2nd supply voltage
|
||||
- ESC_slew_rate.lua example script supports testing ESCs
|
||||
- Filesystem CRC32 check to allow scripts to check module versions
|
||||
- forced arming support
|
||||
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
|
||||
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
|
||||
- Halo6000 EFI driver can log all CAN packets for easier debugging
|
||||
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
|
||||
- I2C:transfer support
|
||||
- IMU gyros_consistent and accels_consistent bindings added
|
||||
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
|
||||
- INS bindings for is calibrating, gyro and accel sensor values
|
||||
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
|
||||
- Logging of booleans supported
|
||||
- Lua language checks improved (finds more errors)
|
||||
- MAVLink commands can be called from scripting
|
||||
- MCU voltage binding (see analog:mcu_voltage)
|
||||
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
|
||||
- "open directory failed" false warning when scripts in ROMFS fixed
|
||||
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
|
||||
- Pass by reference values are always initialized
|
||||
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
|
||||
- plane_aerobatics.lua minor enhancements
|
||||
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
|
||||
- "require" function failures in rare circumstances fixed
|
||||
- "require" function works for modules in ROMFS (e.g. not on SD card)
|
||||
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
|
||||
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
|
||||
- SD card formatting supported
|
||||
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
|
||||
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
|
||||
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
|
||||
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
|
||||
- Temperature sensor bindings added
|
||||
- uint64 support
|
||||
- Various performance and memory usage optimizations
|
||||
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
|
||||
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
|
||||
|
||||
13) GCS / mavlink related changes and fixes
|
||||
|
||||
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
|
||||
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
|
||||
- Deny attempts to upload two missions simultaneously
|
||||
- Fence and Rally points may be uploaded using FTP
|
||||
- GPS_INPUT and HIL_GPS handles multiple GPSs
|
||||
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
|
||||
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
|
||||
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
|
||||
- MAV_CMD_SET_HAGL support (Plane only)
|
||||
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
|
||||
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
|
||||
- Message interval supports TERRAIN_REPORT msg
|
||||
- Mission upload may be cancelled using MISSION_CLEAR_ALL
|
||||
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
|
||||
- RC_CHANNELS_RAW deprecated
|
||||
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
|
||||
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
|
||||
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
|
||||
|
||||
14) Logging enhancements and fixes
|
||||
|
||||
- AC_PID resets and I-term sets logged
|
||||
- ANG provides attitude at high rate (equivalent to ATT)
|
||||
- ATT logs angles as floats (better resolution than ints)
|
||||
- CAND message gets driver index
|
||||
- DCM log message includes roll/pitch and yaw error
|
||||
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
|
||||
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
|
||||
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
|
||||
- FMT messages written as required instead of all at beginning
|
||||
- Logging restarted after download completes when LOG_DISARMED = 1
|
||||
- MISE msg logs active mission command (CMD logged when commands are uploaded)
|
||||
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
|
||||
- RPM sensor logging gets instance field, quality and health fields
|
||||
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
|
||||
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
|
||||
- UART data rates logged at 1hz (see UART message)
|
||||
|
||||
15) ROS2 / DDS support
|
||||
|
||||
- Airspeed published
|
||||
- Battery topic reports all available batteries
|
||||
- Compile-time configurable rates for each publisher
|
||||
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
|
||||
- GPS global origin published at 1 Hz
|
||||
- High frequency raw imu data transmission
|
||||
- Joystick support
|
||||
- Support sending waypoints to Copter and Rover
|
||||
- Remove the XML refs file in favor of binary entity creation
|
||||
|
||||
16) Safety related enhancements and fixes
|
||||
|
||||
- Accel/Gyro inconsistent message fixed for using with only single IMU
|
||||
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
|
||||
- Far from EKF origin pre-arm check removed (Copter only)
|
||||
- Fence breach warning message slightly improved
|
||||
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
|
||||
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
|
||||
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
|
||||
- LEDs flash green lights based on EKF location not GPS
|
||||
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
|
||||
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
|
||||
- Pre-arm check if OpenDroneID is compiled in but disabled
|
||||
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
|
||||
- Pre-arm checks alert user more quickly on failure
|
||||
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
|
||||
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
|
||||
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
|
||||
- Warning of duplicate SERIALx_PROTOCOL = RCIN
|
||||
|
||||
17) Other bug fixes and minor enhancements
|
||||
|
||||
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
|
||||
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
|
||||
- Bootloader rejects allocation of broadcast node ID
|
||||
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
|
||||
- Dijkstras fix to correct use of uninitialised variable
|
||||
- DShot rates are not limited by NeoPixel rates
|
||||
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
|
||||
- Filesystem does not show entries for empty @ files
|
||||
- Filesystem efficiency improvements when reading files
|
||||
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
|
||||
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
|
||||
- Internal error thrown if we lose parameters due to saving queue being too small
|
||||
- MAVLink via DroneCAN baud rate fix
|
||||
- SPI pins may also be used as GPIOs
|
||||
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
|
||||
|
||||
18) Developer focused fixes and enhancements
|
||||
|
||||
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
|
||||
- Cygwin build fix for non-SITL builds
|
||||
- Cygwin build fixed with malloc wrap
|
||||
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
|
||||
- EKF3 code generator documentation and cleanup
|
||||
- GPS jamming simulator added
|
||||
- MacOS compiler warnings reduced
|
||||
- SFML joystick support
|
||||
- SITL support for OpenBSD
|
||||
- Text warning if older Fence or Rally point protocols are used
|
||||
------------------------------------------------------------------
|
||||
Release 4.5.7 08 Oct 2024
|
||||
|
||||
Changes from 4.5.7-beta1
|
||||
|
@ -107,7 +107,7 @@ void Plane::init_rc_out_main()
|
||||
*/
|
||||
void Plane::init_rc_out_aux()
|
||||
{
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
servos_output();
|
||||
|
||||
|
@ -22,7 +22,7 @@
|
||||
/*****************************************
|
||||
* Throttle slew limit
|
||||
*****************************************/
|
||||
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||
void Plane::throttle_slew_limit()
|
||||
{
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
const bool do_throttle_slew = (control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode());
|
||||
@ -32,7 +32,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||
|
||||
if (!do_throttle_slew) {
|
||||
// only do throttle slew limiting in modes where throttle control is automatic
|
||||
SRV_Channels::set_slew_rate(func, 0.0, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, 0.0, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, 0.0, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, 0.0, 100, G_Dt);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -55,7 +57,9 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||
slewrate = g.takeoff_throttle_slewrate;
|
||||
}
|
||||
#endif
|
||||
SRV_Channels::set_slew_rate(func, slewrate, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttle, slewrate, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleLeft, slewrate, 100, G_Dt);
|
||||
SRV_Channels::set_slew_rate(SRV_Channel::k_throttleRight, slewrate, 100, G_Dt);
|
||||
}
|
||||
|
||||
/* We want to suppress the throttle if we think we are on the ground and in an autopilot controlled throttle mode.
|
||||
@ -619,6 +623,11 @@ void Plane::set_throttle(void)
|
||||
// throttle is suppressed (above) to zero in final flare in auto mode, but we allow instead thr_min if user prefers, eg turbines:
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.throttle_min.get());
|
||||
|
||||
} else if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF)
|
||||
&& (aparm.takeoff_throttle_idle.get() > 0)
|
||||
) {
|
||||
// we want to spin at idle throttle before the takeoff conditions are met
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.takeoff_throttle_idle.get());
|
||||
} else {
|
||||
// default
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
|
||||
@ -788,8 +797,6 @@ void Plane::servos_twin_engine_mix(void)
|
||||
} else {
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right);
|
||||
throttle_slew_limit(SRV_Channel::k_throttleLeft);
|
||||
throttle_slew_limit(SRV_Channel::k_throttleRight);
|
||||
}
|
||||
}
|
||||
|
||||
@ -853,8 +860,8 @@ void Plane::set_servos(void)
|
||||
// start with output corked. the cork is released when we run
|
||||
// servos_output(), which is run from all code paths in this
|
||||
// function
|
||||
SRV_Channels::cork();
|
||||
|
||||
AP::srv().cork();
|
||||
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the plane. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
@ -908,7 +915,7 @@ void Plane::set_servos(void)
|
||||
airbrake_update();
|
||||
|
||||
// slew rate limit throttle
|
||||
throttle_slew_limit(SRV_Channel::k_throttle);
|
||||
throttle_slew_limit();
|
||||
|
||||
int8_t min_throttle = 0;
|
||||
#if AP_ICENGINE_ENABLED
|
||||
@ -1012,7 +1019,8 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void)
|
||||
*/
|
||||
void Plane::servos_output(void)
|
||||
{
|
||||
SRV_Channels::cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
|
||||
// support twin-engine aircraft
|
||||
servos_twin_engine_mix();
|
||||
@ -1050,7 +1058,7 @@ void Plane::servos_output(void)
|
||||
|
||||
SRV_Channels::output_ch_all();
|
||||
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
|
||||
if (g2.servo_channels.auto_trim_enabled()) {
|
||||
servos_auto_trim();
|
||||
|
@ -289,9 +289,6 @@ void Tailsitter::output(void)
|
||||
return;
|
||||
}
|
||||
|
||||
float tilt_left = 0.0f;
|
||||
float tilt_right = 0.0f;
|
||||
|
||||
// throttle 0 to 1
|
||||
float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01;
|
||||
|
||||
@ -341,6 +338,10 @@ void Tailsitter::output(void)
|
||||
// set AP_MotorsMatrix throttles for forward flight
|
||||
motors->output_motor_mask(throttle, motor_mask, plane.rudder_dt);
|
||||
|
||||
// No tilt output unless forward gain is set
|
||||
float tilt_left = 0.0;
|
||||
float tilt_right = 0.0;
|
||||
|
||||
// in forward flight: set motor tilt servos and throttles using FW controller
|
||||
if (vectored_forward_gain > 0) {
|
||||
// remove scaling from surface speed scaling and apply throttle scaling
|
||||
@ -398,8 +399,11 @@ void Tailsitter::output(void)
|
||||
}
|
||||
|
||||
// output tilt motors
|
||||
tilt_left = 0.0f;
|
||||
tilt_right = 0.0f;
|
||||
|
||||
// No output unless hover gain is set
|
||||
float tilt_left = 0.0;
|
||||
float tilt_right = 0.0;
|
||||
|
||||
if (vectored_hover_gain > 0) {
|
||||
const float hover_throttle = motors->get_throttle_hover();
|
||||
const float output_throttle = motors->get_throttle();
|
||||
@ -438,8 +442,10 @@ void Tailsitter::output(void)
|
||||
tailsitter_motors->set_min_throttle(0.0);
|
||||
}
|
||||
|
||||
tilt_left = 0.0f;
|
||||
tilt_right = 0.0f;
|
||||
// No tilt output unless hover gain is set
|
||||
float tilt_left = 0.0;
|
||||
float tilt_right = 0.0;
|
||||
|
||||
if (vectored_hover_gain > 0) {
|
||||
// thrust vectoring VTOL modes
|
||||
tilt_left = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft);
|
||||
|
@ -290,7 +290,7 @@ void Sub::one_hz_loop()
|
||||
}
|
||||
|
||||
// update assigned functions and enable auxiliary servos
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log terrain data
|
||||
|
@ -369,10 +369,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_CURRENT_WAYPOINT,
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
@ -437,7 +443,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
#endif
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
|
||||
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
||||
@ -962,3 +969,47 @@ uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
|
||||
return 0;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Sub::send_available_mode(uint8_t index) const
|
||||
{
|
||||
const Mode* modes[] {
|
||||
&sub.mode_manual,
|
||||
&sub.mode_stabilize,
|
||||
&sub.mode_acro,
|
||||
&sub.mode_althold,
|
||||
&sub.mode_surftrak,
|
||||
&sub.mode_poshold,
|
||||
&sub.mode_auto,
|
||||
&sub.mode_guided,
|
||||
&sub.mode_circle,
|
||||
&sub.mode_surface,
|
||||
&sub.mode_motordetect,
|
||||
};
|
||||
|
||||
const uint8_t mode_count = ARRAY_SIZE(modes);
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name = modes[index_zero]->name();
|
||||
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -37,6 +37,10 @@ protected:
|
||||
|
||||
uint64_t capabilities() const override;
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
void handle_message(const mavlink_message_t &msg) override;
|
||||
|
@ -72,6 +72,9 @@ public:
|
||||
virtual const char *name() const = 0;
|
||||
virtual const char *name4() const = 0;
|
||||
|
||||
// returns a unique number specific to this mode
|
||||
virtual Mode::Number number() const = 0;
|
||||
|
||||
// functions for reporting to GCS
|
||||
virtual bool get_wp(Location &loc) { return false; }
|
||||
virtual int32_t wp_bearing() const { return 0; }
|
||||
@ -202,6 +205,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "MANUAL"; }
|
||||
const char *name4() const override { return "MANU"; }
|
||||
Mode::Number number() const override { return Mode::Number::MANUAL; }
|
||||
};
|
||||
|
||||
|
||||
@ -224,6 +228,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "ACRO"; }
|
||||
const char *name4() const override { return "ACRO"; }
|
||||
Mode::Number number() const override { return Mode::Number::ACRO; }
|
||||
};
|
||||
|
||||
|
||||
@ -246,6 +251,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "STABILIZE"; }
|
||||
const char *name4() const override { return "STAB"; }
|
||||
Mode::Number number() const override { return Mode::Number::STABILIZE; }
|
||||
};
|
||||
|
||||
|
||||
@ -272,6 +278,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "ALT_HOLD"; }
|
||||
const char *name4() const override { return "ALTH"; }
|
||||
Mode::Number number() const override { return Mode::Number::ALT_HOLD; }
|
||||
};
|
||||
|
||||
|
||||
@ -293,6 +300,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "SURFTRAK"; }
|
||||
const char *name4() const override { return "STRK"; }
|
||||
Mode::Number number() const override { return Mode::Number::SURFTRAK; }
|
||||
|
||||
private:
|
||||
|
||||
@ -342,6 +350,8 @@ protected:
|
||||
|
||||
const char *name() const override { return "GUIDED"; }
|
||||
const char *name4() const override { return "GUID"; }
|
||||
Mode::Number number() const override { return Mode::Number::GUIDED; }
|
||||
|
||||
autopilot_yaw_mode get_default_auto_yaw_mode(bool rtl) const;
|
||||
|
||||
private:
|
||||
@ -387,6 +397,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "AUTO"; }
|
||||
const char *name4() const override { return "AUTO"; }
|
||||
Mode::Number number() const override { return Mode::Number::AUTO; }
|
||||
|
||||
private:
|
||||
void auto_wp_run();
|
||||
@ -417,6 +428,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "POSHOLD"; }
|
||||
const char *name4() const override { return "POSH"; }
|
||||
Mode::Number number() const override { return Mode::Number::POSHOLD; }
|
||||
};
|
||||
|
||||
|
||||
@ -439,6 +451,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "CIRCLE"; }
|
||||
const char *name4() const override { return "CIRC"; }
|
||||
Mode::Number number() const override { return Mode::Number::CIRCLE; }
|
||||
};
|
||||
|
||||
class ModeSurface : public Mode
|
||||
@ -460,6 +473,7 @@ protected:
|
||||
|
||||
const char *name() const override { return "SURFACE"; }
|
||||
const char *name4() const override { return "SURF"; }
|
||||
Mode::Number number() const override { return Mode::Number::CIRCLE; }
|
||||
};
|
||||
|
||||
|
||||
@ -482,4 +496,5 @@ protected:
|
||||
|
||||
const char *name() const override { return "MOTORDETECT"; }
|
||||
const char *name4() const override { return "DETE"; }
|
||||
Mode::Number number() const override { return Mode::Number::MOTOR_DETECT; }
|
||||
};
|
||||
|
@ -18,11 +18,12 @@ void Sub::motors_output()
|
||||
verify_motor_test();
|
||||
} else {
|
||||
motors.set_interlock(true);
|
||||
SRV_Channels::cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
SRV_Channels::calc_pwm();
|
||||
SRV_Channels::output_ch_all();
|
||||
motors.output();
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -210,7 +210,7 @@ void Blimp::one_hz_loop()
|
||||
#endif
|
||||
|
||||
// update assigned functions and enable auxiliary servos
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
AP_Notify::flags.flying = !ap.land_complete;
|
||||
|
||||
|
@ -327,10 +327,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_CURRENT_WAYPOINT, // MISSION_CURRENT
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
@ -395,7 +401,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
#endif
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
static const ap_message STREAM_ADSB_msgs[] = {
|
||||
MSG_ADSB_VEHICLE,
|
||||
@ -608,3 +615,41 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
|
||||
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Blimp::send_available_mode(uint8_t index) const
|
||||
{
|
||||
const Mode* modes[] {
|
||||
&blimp.mode_land,
|
||||
&blimp.mode_manual,
|
||||
&blimp.mode_velocity,
|
||||
&blimp.mode_loiter,
|
||||
&blimp.mode_rtl,
|
||||
};
|
||||
|
||||
const uint8_t mode_count = ARRAY_SIZE(modes);
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name = modes[index_zero]->name();
|
||||
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -48,6 +48,10 @@ protected:
|
||||
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
|
||||
#endif
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
void handle_message(const mavlink_message_t &msg) override;
|
||||
|
14
Blimp/mode.h
14
Blimp/mode.h
@ -52,6 +52,9 @@ public:
|
||||
virtual const char *name() const = 0;
|
||||
virtual const char *name4() const = 0;
|
||||
|
||||
// returns a unique number specific to this mode
|
||||
virtual Mode::Number number() const = 0;
|
||||
|
||||
virtual bool is_landing() const
|
||||
{
|
||||
return false;
|
||||
@ -159,6 +162,8 @@ protected:
|
||||
return "MANU";
|
||||
}
|
||||
|
||||
Mode::Number number() const override { return Mode::Number::MANUAL; }
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
@ -201,6 +206,8 @@ protected:
|
||||
return "VELY";
|
||||
}
|
||||
|
||||
Mode::Number number() const override { return Mode::Number::VELOCITY; }
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
@ -244,6 +251,8 @@ protected:
|
||||
return "LOIT";
|
||||
}
|
||||
|
||||
Mode::Number number() const override { return Mode::Number::LOITER; }
|
||||
|
||||
private:
|
||||
Vector3f target_pos;
|
||||
float target_yaw;
|
||||
@ -286,6 +295,8 @@ protected:
|
||||
return "LAND";
|
||||
}
|
||||
|
||||
Mode::Number number() const override { return Mode::Number::LAND; }
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
@ -328,4 +339,7 @@ protected:
|
||||
{
|
||||
return "RTL";
|
||||
}
|
||||
|
||||
Mode::Number number() const override { return Mode::Number::RTL; }
|
||||
|
||||
};
|
||||
|
@ -78,8 +78,10 @@ void Blimp::motors_output()
|
||||
// output any servo channels
|
||||
SRV_Channels::calc_pwm();
|
||||
|
||||
auto &srv = AP::srv();
|
||||
|
||||
// cork now, so that all channel outputs happen at once
|
||||
SRV_Channels::cork();
|
||||
srv.cork();
|
||||
|
||||
// update output on any aux channels, for manual passthru
|
||||
SRV_Channels::output_ch_all();
|
||||
@ -88,5 +90,5 @@ void Blimp::motors_output()
|
||||
motors->output();
|
||||
|
||||
// push all channels
|
||||
SRV_Channels::push();
|
||||
}
|
||||
srv.push();
|
||||
}
|
||||
|
@ -38,7 +38,7 @@ void Blimp::init_rc_in()
|
||||
void Blimp::init_rc_out()
|
||||
{
|
||||
// enable aux servos to cope with multiple output channels per motor
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// refresh auxiliary channel to function map
|
||||
SRV_Channels::update_aux_servo_function();
|
||||
|
@ -541,10 +541,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
MSG_CURRENT_WAYPOINT,
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#if GPS_MAX_RECEIVERS > 1
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
|
||||
MSG_GPS2_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
|
||||
MSG_GPS2_RTK,
|
||||
#endif
|
||||
MSG_NAV_CONTROLLER_OUTPUT,
|
||||
@ -613,7 +619,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
||||
#endif
|
||||
};
|
||||
static const ap_message STREAM_PARAMS_msgs[] = {
|
||||
MSG_NEXT_PARAM
|
||||
MSG_NEXT_PARAM,
|
||||
MSG_AVAILABLE_MODES
|
||||
};
|
||||
static const ap_message STREAM_ADSB_msgs[] = {
|
||||
MSG_ADSB_VEHICLE,
|
||||
@ -1148,3 +1155,54 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
|
||||
return 0;
|
||||
}
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t GCS_MAVLINK_Rover::send_available_mode(uint8_t index) const
|
||||
{
|
||||
const Mode* modes[] {
|
||||
&rover.mode_manual,
|
||||
&rover.mode_acro,
|
||||
&rover.mode_steering,
|
||||
&rover.mode_hold,
|
||||
&rover.mode_loiter,
|
||||
#if MODE_FOLLOW_ENABLED
|
||||
&rover.mode_follow,
|
||||
#endif
|
||||
&rover.mode_simple,
|
||||
&rover.g2.mode_circle,
|
||||
&rover.mode_auto,
|
||||
&rover.mode_rtl,
|
||||
&rover.mode_smartrtl,
|
||||
&rover.mode_guided,
|
||||
&rover.mode_initializing,
|
||||
#if MODE_DOCK_ENABLED
|
||||
(Mode *)rover.g2.mode_dock_ptr,
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t mode_count = ARRAY_SIZE(modes);
|
||||
|
||||
// Convert to zero indexed
|
||||
const uint8_t index_zero = index - 1;
|
||||
if (index_zero >= mode_count) {
|
||||
// Mode does not exist!?
|
||||
return mode_count;
|
||||
}
|
||||
|
||||
// Ask the mode for its name and number
|
||||
const char* name = modes[index_zero]->name4();
|
||||
const uint8_t mode_number = (uint8_t)modes[index_zero]->mode_number();
|
||||
|
||||
mavlink_msg_available_modes_send(
|
||||
chan,
|
||||
mode_count,
|
||||
index,
|
||||
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
|
||||
mode_number,
|
||||
0, // MAV_MODE_PROPERTY bitmask
|
||||
name
|
||||
);
|
||||
|
||||
return mode_count;
|
||||
}
|
||||
|
@ -40,6 +40,10 @@ protected:
|
||||
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
|
||||
#endif
|
||||
|
||||
// Send the mode with the given index (not mode number!) return the total number of modes
|
||||
// Index starts at 1
|
||||
uint8_t send_available_mode(uint8_t index) const override;
|
||||
|
||||
private:
|
||||
|
||||
void handle_message(const mavlink_message_t &msg) override;
|
||||
|
@ -1,5 +1,429 @@
|
||||
Rover Release Notes:
|
||||
------------------------------------------------------------------
|
||||
Release 4.6.0-beta 13 Nov 2024
|
||||
|
||||
Changes from 4.5.7
|
||||
|
||||
1) Board specific changes
|
||||
|
||||
- AnyLeaf H7 supports compass and onboard logging
|
||||
- Blitz743Pro supports CAN
|
||||
- BlueRobotics Navigator supports BMP390 baro
|
||||
- Bootloader ECC failure check fixed on boards with >128k bootloader space (e.g CubeRed)
|
||||
- CB Unmanned Stamp H743 support
|
||||
- ClearSky CSKY405 support
|
||||
- CUAV-7-Nano default batt monitor fixed
|
||||
- CubeRed bootloader fixes including disabling 2nd core by default
|
||||
- CubeRed supports PPP networking between primary and secondary MCU
|
||||
- CubeRedPrimary supports external compasses
|
||||
- ESP32 main loop rate improvements
|
||||
- ESP32 RC input fixes and wifi connection reliability improved
|
||||
- ESP32 safety switch and GPIO pin support
|
||||
- FlyingMoon no longer support MAX7456
|
||||
- Flywoo F405HD-AIOv2 ELRS RX pin pulled high during boot
|
||||
- Flywoo H743 Pro support
|
||||
- Flywoo/Goku F405 HD 1-2S ELRS AIO v2
|
||||
- FlywooF745 supports DPS310 baro
|
||||
- FPV boards lose SMBus battery support (to save flash)
|
||||
- GEPRC F745BTHD support
|
||||
- GEPRCF745BTHD loses parachute support, non-BMP280 baros (to save flash)
|
||||
- Here4FC bootloader fix for mismatch between RAM0 and periph that could prevent firmware updates
|
||||
- Holybro Kakute F4 Wing support
|
||||
- iFlight 2RAW H743 supports onboard logging
|
||||
- JFB110 supports measuring servo rail voltage
|
||||
- JFB110 supports safety switch LED
|
||||
- JHEM-JHEF405 bootloader supports firmware updates via serial
|
||||
- JHEMCU GF30H743 HD support
|
||||
- JHEMCU-GF16-F405 autopilot support
|
||||
- JHEMCU-GSF405A becomes FPV board (to save flash)
|
||||
- KakuteF7 only supports BMP280 baro (to save flash)
|
||||
- KakuteH7Mini supports ICM42688 IMU
|
||||
- Linux auto detection of GPS baud rate fixed
|
||||
- Linux board scheduler jitter reduced
|
||||
- Linux board shutdown fixes
|
||||
- MakeFlyEasy PixPilot-V6Pro support
|
||||
- MatekF405, Pixhawk1-1M-bdshot, revo-mini loses blended GPS (to save flash)
|
||||
- MatekH7A3 support Bi-directional DShot
|
||||
- MicoAir405v2 and MicoAir405Mini support optical flow and OSD
|
||||
- MicoAir743 internal compass orientation fixed
|
||||
- MicroAir405Mini, MicroAir743, NxtPX4v2 support
|
||||
- MicroAir405v2 Bi-directional DShot and LED DMA fixes
|
||||
- MicroAir405v2 defined as FPV board with reduced features (to save flash)
|
||||
- ModalAI VOXL2 support including Starling 2 and Starling 2 max
|
||||
- mRo Control Zero Classic supports servo rail analog input
|
||||
- mRo KitCAN revC fixed
|
||||
- Mugin MUPilot support
|
||||
- OmnibusF7v2 loses quadplane support (to save flash)
|
||||
- Pixhack-v3 board added (same as fmuv3)
|
||||
- Pixhawk6C bootloader supports flashing firmware from SD card
|
||||
- RadiolinkPIX6 imu orientation fixed
|
||||
- RadiolinkPIX6 supports SPA06 baro
|
||||
- ReaperF745 V4 FC supports MPU6000 IMU
|
||||
- RPI5 support
|
||||
- SDModelH7v2 SERIAL3/7/9_PROTOCOL param defaults changed
|
||||
- Solo serial ports default to MAVLink1
|
||||
- SpeedyBeeF405Wing gets Bi-directional DShot
|
||||
- SpeedyBeeF405WING loses landing gear support, some camera gimbals (to save flash)
|
||||
- Spektreworks boom board support
|
||||
- TrueNavPro-G4 SPI does not share DMA
|
||||
- X-MAV AP-H743v2 support
|
||||
|
||||
2) AHRS/EKF enhancements and fixes
|
||||
|
||||
- AHRS_OPTION to disable fallback to DCM (affects Plane and Rover, Copter never falls back)
|
||||
- AHRS_OPTION to disable innovation check for airspeed sensor
|
||||
- Airspeed sensor health check fixed when using multiple sensors and AHRS affinity
|
||||
- DCM support for MAV_CMD_EXTERNAL_WIND_ESTIMATE (Plane only)
|
||||
- EK2 supports disabling external nav (see EK2_OPTIONS)
|
||||
- EK3 External Nav position jump after switch from Optical flow removed (see EK3_SRC_OPTION=1)
|
||||
- EK3 uses filtered velocity corrections for IMU position
|
||||
- EKF2, EKF3, ExternalAHRS all use common origin
|
||||
- EKF3 accepts set origin even when using GPS
|
||||
- EKF3 allows earth-frame fields to be estimated with an origin but no GPS
|
||||
- EKF3 copes better with GPS jamming
|
||||
- EKF3 logs mag fusion selection to XKFS
|
||||
- EKF3 wind estimation when using GPS-for-yaw fixed
|
||||
- External AHRS improvements including handling variances, pre-arm origin check
|
||||
- Inertial Labs External AHRS fixes
|
||||
- VectorNav driver fix for handling of error from sensor
|
||||
- VectorNav External AHRS enhancements including validation of config commands and logging improvements
|
||||
- VectorNav support for sensors outside VN-100 and VN-300
|
||||
|
||||
3) Driver enhancements and bug fixes
|
||||
|
||||
- ADSB fix to display last character in status text sent to GCS
|
||||
- Ainstein LR-D1 radar support
|
||||
- Airspeed ASP5033 whoami check fixed when autopilot rebooted independently of the sensor
|
||||
- AIRSPEED message sent to GCS
|
||||
- Analog temperature sensor extended to 5th order polynomial (see TEMP_A5)
|
||||
- ARSPD_OPTIONS to report calibration offset to GCS
|
||||
- Baro EAS2TAS conversions continuously calculated reducing shocks to TECS (Plane only)
|
||||
- Baro provides improved atmospheric model for high altitude flight
|
||||
- BARO_ALT_OFFSET slew slowed to keep EKF happy
|
||||
- BATTx_ESC_MASK param supports flexible mapping of ESCs to batteries
|
||||
- BATTx_OPTION to not send battery voltage, current, etc to GCS
|
||||
- Benewake RDS02U radar support
|
||||
- Bi-directional DShot on IOMCU supports reversible mask
|
||||
- Bi-directional DShot telemetry support on F103 8Mhz IOMCUs
|
||||
- BMM350 compass support
|
||||
- CAN rangefinders and proximity sensors may share a CAN bus (allows NRA24 and MR72 on a single CAN bus)
|
||||
- Compass calibration world magnetic model checks can use any position source (e.g. not just GPS)
|
||||
- CRSF baro and vertical speeed fixed
|
||||
- CRSF RX bind command support
|
||||
- DroneCAN battery monitor check to avoid memory corruption when type changed
|
||||
- DroneCAN DNA server fixes including removing use of invalid node IDs, faster ID allocation, elimination of rare inability to save info
|
||||
- DroneCAN EFI health check fix
|
||||
- DroneCAN ESC battery monitors calculate consumed mah
|
||||
- DroneCAN ESCs forced to zero when disarmed
|
||||
- DroneCAN RPM message support
|
||||
- DroneCAN timeout fix for auxiliary frames
|
||||
- DroneCAN to serial tunneling params accepts short-hand baud rates (e.g. '57' for '57600')
|
||||
- F9P, F10-N and Zed-F9P support for GPSx_GNSS_MODE to turn on/off SBAS, Galileo, Beidou and Glonass
|
||||
- FuelLevel battery monitor fix to report capacity
|
||||
- GPS_xxx params renamed to GPS1_xxx, GPS_xxx2 renamed to GPS2_xxx
|
||||
- Hirth EFI logging includes modified throttle
|
||||
- Hirth ICEngine supports reversed crank direction (see ICE_OPTIONS parameter)
|
||||
- Hott and LTM telemetry deprecated (still available through custom build server)
|
||||
- i-BUS telemetry support
|
||||
- ICE_PWM_IGN_ON, ICE_PWM_IGN_OFF, ICE_PWM_STRT_ON, ICE_PWM_STRT_OFF replaced with SERVOx_MIN/MAX/REVERSED (Plane only)
|
||||
- ICE_START_CHAN replaced with RC aux function (Plane only)
|
||||
- ICEngine retry max added (see ICE_STRT_MX_RTRY)
|
||||
- IE 2400 generator error message severity to GCS improved
|
||||
- INA2xx battery monitor support (reads temp, gets MAX_AMPS and SHUNT params)
|
||||
- MCP9600 temperature sensor I2C address fixed
|
||||
- MLX90614 temperature sensor support
|
||||
- MSP GPS ground course scaling fixed
|
||||
- MSP RC uses scaled RC inputs (fixes issue with RCx_REVERSED having no effect)
|
||||
- Networking supports reconnection to TCP server or client
|
||||
- OSD params for adjusting horizontal spacing and vertical extension (see OSD_SB_H_OFS, OSD_SB_V_EXT)
|
||||
- Relay inverted output support (see RELAYx_INVERTED parameter)
|
||||
- ROMFS efficiency improvements
|
||||
- RS-485 driver enable RTS flow control
|
||||
- Sagetech MXS ADSP altitude fix (now uses abs alt instead of terrain alt)
|
||||
- Septentrio GPS sat count correctly drops to zero when 255 received
|
||||
- Septentrio supports selecting constellations (see GPS_GNSS_MODE)
|
||||
- Single LED for user notification supported
|
||||
- SPA06 baro supported
|
||||
- Sum battery monitor optionally reports minimum voltage instead of average
|
||||
- Sum battery monitor reports average temp
|
||||
- Torqeedo dual motor support (see TRQ1, TRQ2 params)
|
||||
- Ublox GPS driver uses 64 bit time for PPS interrupt (avoids possible dropout at 1hour and 12 minutes)
|
||||
- UBlox GPS time ignored until at least 2D fix
|
||||
- VideoTX supports additional freq bands (RushFPV 3.3Ghz)
|
||||
- Volz logs desired and actual position, voltage, current, motor and PCB temp
|
||||
- Volz server feedback and logging fixed
|
||||
- Volz servo output in its own thread resulting in smoother movements
|
||||
- W25N02KV flash support
|
||||
|
||||
4) Networking enhancements and fixes
|
||||
|
||||
- Allow multiple UDP clients to connect/disconnect/reconnect
|
||||
- Ethernet supports faster log downloading (raised SDMMC clock limit on H7)
|
||||
|
||||
5) Camera and gimbal enhancements
|
||||
|
||||
- Alexmos precision improved slightly
|
||||
- CAMERA_CAPTURE_STATUS mavlink msg sent to GCS (reports when images taken or video recorded, used by QGC)
|
||||
- CAMERA_FOV_STATUS mavlink reports lat,lon of what camera is pointing at
|
||||
- DO_MOUNT_CONTROL yaw angle interpreted as body-frame (was incorrectly being interpreted as earth-frame)
|
||||
- Dual serial camera gimbal mounts fixed
|
||||
- Lua script bindings to send CAMERA_INFORMATION and VIDEO_STREAM_INFORMATION messages to GCS
|
||||
- Retract Mount2 aux function added (see RCx_OPTION = 113)
|
||||
- Servo gimbal reported angles respect roll, pitch and yaw limits
|
||||
- Siyi driver sends autopilot location and speed (recorded in images via EXIF)
|
||||
- Siyi picture and video download scripts
|
||||
- Siyi ZT6 and ZT30 support sending min, max temperature (see CAMERA_THERMAL_RANGE msg)
|
||||
- Siyi ZT6 and ZT30 thermal palette can be changed using camera-change-setting.lua script
|
||||
- Siyi ZT6 hardware id and set-lens fixed
|
||||
- Topotek gimbal support
|
||||
- Trigger distance ignores GPS status and only uses EKF reported location
|
||||
|
||||
6) Harmonic notch enhancements
|
||||
|
||||
- Harmonic notch is active in forward flight on quadplanes
|
||||
- Harmonic notch filter freq clamping and disabling reworked
|
||||
- Harmonic notch handles negative ESC RPMs
|
||||
- Harmonic notch supports per-motor throttle-based harmonic notch
|
||||
|
||||
7) Copter specific enhancements and bug fixes
|
||||
|
||||
- Attitude control fix to dt update order (reduces rate controller noise)
|
||||
- Auto mode fix to avoid prematurely advancing to next waypoint if given enough time
|
||||
- Auto mode small target position jump when takeoff completes removed
|
||||
- Auto mode yaw drift when passing WP removed if CONDITION_YAW command used and WP_YAW_BEHAVIOR = 0/None
|
||||
- Auto, Guided flight mode pause RC aux switch (see RCx_OPTION = 178)
|
||||
- AutoRTL (e.g. DO_LAND_START) uses copter stopping point to decide nearest mission command
|
||||
- AutoRTL mode supports DO_RETURN_PATH_START (Copter, Heli only)
|
||||
- AutoTune fix to prevent spool up after landing
|
||||
- AutoTune performance and safety enhancements (less chance of ESC desync, fails when vehicle likely can't be tuned well)
|
||||
- Autotune test gains RC aux switch function allows testing gains in any mode (see RCx_OPTION = 180)
|
||||
- Config error avoided if auto mode is paused very soon after poweron
|
||||
- FLIGHT_OPTIONS bit added to require position estimate before arming
|
||||
- Follow mode slowdown calcs fixed when target is moving
|
||||
- Ground oscillation suppressed by reducing gains (see ATC_LAND_R/P/Y_MULT)
|
||||
- Guided mode internal error fix when taking off using SET_ATTITUDE_CONTROL message
|
||||
- Guided mode internal error resolved when switching between thrust or climb rate based altitude control
|
||||
- Guided mode yaw fixed when WP_YAW_BEHAVIOR = 0/None and CONDITION_YAW command received containing relative angle
|
||||
- Landing detector fixed when in stabilize mode at full throttle but aircraft is upside down
|
||||
- Landing detector logging added to ease support (see LDET message)
|
||||
- Loiter unlimited command accepts NaNs (QGC sends these)
|
||||
- Mavlink SYSTEM_STATUS set to BOOT during initialisation
|
||||
- MOT_PWM_TYPE of 9 (PWMAngle) respects SERVOx_MIN/MAX/TRIM/REVERSED param values
|
||||
- Payload place bug fix when aborted because gripper is already released
|
||||
- RC based tuning (aka CH6 tuning) can use any RC aux function channel (see RCx_OPTION = 219)
|
||||
- RTL_ALT minimum reduced to 30cm
|
||||
- SystemID position controller support (Copter and Heli)
|
||||
- TriCopter motor test and slew-up fixed
|
||||
- WPNAV_SPEED min reduced to 10 cm/s (Copter only)
|
||||
- Loiter mode zeros desired accel when re-entering from Auto during RC failsafe
|
||||
|
||||
8) TradHeli specific enhancements
|
||||
|
||||
- Autorotation yaw behaviour fix
|
||||
- Autotune improvements including using low frequency dwell for feedforward gain tuning and conducting sweep in attitude instead of rate
|
||||
- Blade pitch angle logging added (see SWSH log message)
|
||||
- Constrain cyclic roll for intermeshing
|
||||
- ICE / turbine cool down fix
|
||||
- Inverted flight extended to non manual throttle modes
|
||||
- Inverted flight transitions smoothed and restricted to only Stabilize mode
|
||||
- SWSH logging fix for reversed collectives
|
||||
|
||||
9) Plane specific enhancements and bug fixes
|
||||
|
||||
- AIRSPEED_STALL holds vehicle stall speed and is used for minimum speed scaling
|
||||
- Allow for different orientations of landing rangefinder
|
||||
- Assistance requirements evaluted on mode change
|
||||
- FBWB/CRUISE climb/sink rate limited by TECS limits
|
||||
- FLIGHT_OPTION to immediately climb in AUTO mode (not doing glide slope)
|
||||
- Glider pullup support (available only through custom build server)
|
||||
- Loiter breakout improved to better handle destinations inside loiter circle
|
||||
- Manual mode throttle made consistent with other modes (e.g battery comp and watt limit is done if enabled)
|
||||
- Mavlink GUIDED_CHANGE_ALTITUDE supports terrain altitudes
|
||||
- Minimum throttle not applied during SLT VTOL airbrake (reduces increase in airspeed and alt during back transition)
|
||||
- Q_APPROACH_DIST set minimum distance to use the fixed wing approach logic
|
||||
- Quadplane assistance check enhancements
|
||||
- Quadplane Deca frame support
|
||||
- Quadplane gets smoother takeoff by input shaping target accel and velocity
|
||||
- Servo wiggles in altitude wait staged to be one after another
|
||||
- Set_position_target_global_int accepts MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT frames
|
||||
- Takeoff airspeed control improved (see TKOFF_MODE, TKOFF_THR_MIN)
|
||||
- Takeoff fixes for fence autoenable
|
||||
- Takeoff improvements including less overshoot of TKOFF_ALT
|
||||
- TECS reset along with other controllers (important if plane dropped from balloon)
|
||||
- Tilt quadplane ramp of motors on back transition fixed
|
||||
- Tiltrotor tilt angles logged
|
||||
- TKOFF_THR_MIN applied to SLT transitions
|
||||
- Twin motor planes with DroneCAN ESCs fix to avoid max throttle at arming due to misconfiguration
|
||||
- VTOLs switch to QLAND if a LONG_FAILSAFE is triggered during takeoff
|
||||
|
||||
10) Rover specific enhancements and bug fixes
|
||||
|
||||
- Auto mode reversed state maintained if momentarily switched to Hold mode
|
||||
- Circle mode tracks better and avoids getting stuck at circle edge
|
||||
- Flight time stats fixed
|
||||
- MAV_CMD_NAV_SET_YAW_SPEED deprecated
|
||||
- Omni3Mecanum frame support
|
||||
- Stopping point uses max deceleration (was incorrectly using acceleration)
|
||||
- Wheel rate controller slew rate fix
|
||||
|
||||
11) Antenna Tracker specific enhancements and bug fixes
|
||||
|
||||
- Never track lat,lon of 0,0
|
||||
|
||||
12) Scripting enhancements
|
||||
|
||||
- advance-wp.lua applet supports advancing Auto mode WP via RC switch
|
||||
- AHRS_switch.lua supports switching between EKF2 and EKF3 via RC switch
|
||||
- battery_internal_resistance_check.lua monitors battery resistance
|
||||
- CAN:get_device returns nil for unconfigured CAN device
|
||||
- copter_terrain_brake.lua script added to prevent impact with terrain in Loiter mode (Copter only)
|
||||
- Copter:get_target_location, update_target_location support
|
||||
- crosstrack_restore.lua example allows returning to previous track in Auto (Plane only)
|
||||
- Display text on OLED display supported
|
||||
- Docs improved for many bindings
|
||||
- EFI get_last_update_ms binding
|
||||
- EFI_SkyPower.lua driver accepts 2nd supply voltage
|
||||
- ESC_slew_rate.lua example script supports testing ESCs
|
||||
- Filesystem CRC32 check to allow scripts to check module versions
|
||||
- forced arming support
|
||||
- GPIO get/set mode bindings (see gpio:set_mode, get_mode)
|
||||
- GPS-for-yaw angle binding (see gps:gps_yaw_deg)
|
||||
- Halo6000 EFI driver can log all CAN packets for easier debugging
|
||||
- handle_external_position_estimate binding allows sending position estimate from lua to EKF
|
||||
- I2C:transfer support
|
||||
- IMU gyros_consistent and accels_consistent bindings added
|
||||
- INF_Inject.lua driver more robust to serial errors, improved logging, throttle and ignition control
|
||||
- INS bindings for is calibrating, gyro and accel sensor values
|
||||
- IPV4 address bindings (see SocketAPM_ipv4_addr_to_string) to allow UDP server that responds to individual clients
|
||||
- Logging of booleans supported
|
||||
- Lua language checks improved (finds more errors)
|
||||
- MAVLink commands can be called from scripting
|
||||
- MCU voltage binding (see analog:mcu_voltage)
|
||||
- NMEA 2000 EFI driver (see EFI_NMEA2k.lua)
|
||||
- "open directory failed" false warning when scripts in ROMFS fixed
|
||||
- Param_Controller.lua supports quickly switching between 3 parameter sets via RC switch
|
||||
- Pass by reference values are always initialized
|
||||
- pelco_d_antennatracker.lua applet supports sending Pelco-D via RS-485 to PTZ cameras
|
||||
- plane_aerobatics.lua minor enhancements
|
||||
- REPL applet (read-evaluate-print-loop, see repl.lua) for interactive testing and experimentation
|
||||
- "require" function failures in rare circumstances fixed
|
||||
- "require" function works for modules in ROMFS (e.g. not on SD card)
|
||||
- revert_param.lua supports more params (e.g ATC_RATE_R/P/Y, PTCH2SRV_TCONST, RLL2SRV_TCONST, TECS_)
|
||||
- Scripts may receive mavlink messages which fail CRC (e.g messages which FC does not understand)
|
||||
- SD card formatting supported
|
||||
- Serial device simulation support (allows Lua to feed data to any supported serial protocol for e.g. sensor simulation)
|
||||
- set_target_throttle_rate_rpy allows rate control from scripts (new for Copter)
|
||||
- sitl_standby_sim.lua example shows how to switch between redundant flight controllers using an RC switch
|
||||
- Slung payload oscillation suppression applet added (see copter-slung-payload.lua)
|
||||
- Temperature sensor bindings added
|
||||
- uint64 support
|
||||
- Various performance and memory usage optimizations
|
||||
- VTOL-quicktune.lua minor enhancements including increasing YAW_FLTE_MAX to 8
|
||||
- x-quad-cg-allocation.lua applet corrects for the CoM discrepancy in a quad-X frame
|
||||
|
||||
13) GCS / mavlink related changes and fixes
|
||||
|
||||
- BATTERY2 message deprecated (replaced by BATTERY_STATUS)
|
||||
- CMD_MISSION_START/STOP rejected if first-item/last-item args provided
|
||||
- Deny attempts to upload two missions simultaneously
|
||||
- Fence and Rally points may be uploaded using FTP
|
||||
- GPS_INPUT and HIL_GPS handles multiple GPSs
|
||||
- HIGHRES_IMU mavlink message support (used by companion computers to receive IMU data from FC)
|
||||
- MAV_CMD_COMPONENT_ARM_DISARM accepts force arm magic value of 21196
|
||||
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE support
|
||||
- MAV_CMD_SET_HAGL support (Plane only)
|
||||
- MAVFTP respects TX buffer flow control to improve FTP on low bandwidth links
|
||||
- MAVLink receiver support (RADIO_RC_CHANNELS mavlink message)
|
||||
- Message interval supports TERRAIN_REPORT msg
|
||||
- Mission upload may be cancelled using MISSION_CLEAR_ALL
|
||||
- MOUNT_CONFIGURE, MOUNT_CONTROL messages deprecated
|
||||
- RC_CHANNELS_RAW deprecated
|
||||
- Serial passthrough supports parity allowing STM32CubeProgrammer to be used to program FrSky R9 receivers
|
||||
- SET_ATTITUDE_TARGET angular rate input frame fixed (Copter only)
|
||||
- TIMESYNC and NAMED_VALUE_FLOAT messages not sent on high latency MAVLink ports
|
||||
|
||||
14) Logging enhancements and fixes
|
||||
|
||||
- AC_PID resets and I-term sets logged
|
||||
- ANG provides attitude at high rate (equivalent to ATT)
|
||||
- ATT logs angles as floats (better resolution than ints)
|
||||
- CAND message gets driver index
|
||||
- DCM log message includes roll/pitch and yaw error
|
||||
- EDT2 log msg includes stress and status received via extended DShot Telemetry v2
|
||||
- EFI ECYL cylinder head and exhaust temp logs in degC (was Kelvin)
|
||||
- ESCX log msg includes DroneCAN ESCs status, temp, duty cycle and power pct
|
||||
- FMT messages written as required instead of all at beginning
|
||||
- Logging restarted after download completes when LOG_DISARMED = 1
|
||||
- MISE msg logs active mission command (CMD logged when commands are uploaded)
|
||||
- ORGN message logging fixed when set using SET_GPS_GLOBAL_ORIGIN
|
||||
- RPM sensor logging gets instance field, quality and health fields
|
||||
- Short filename support removed (e.g log1.BIN instead of 00000001.BIN)
|
||||
- Temperature sensor logging option for only sensors with no source (see TEMP_LOG)
|
||||
- UART data rates logged at 1hz (see UART message)
|
||||
|
||||
15) ROS2 / DDS support
|
||||
|
||||
- Airspeed published
|
||||
- Battery topic reports all available batteries
|
||||
- Compile-time configurable rates for each publisher
|
||||
- DDS_TIMEOUT_MS and DDS_MAX_RETRY set timeout and num retries when client pings XRCE agent
|
||||
- GPS global origin published at 1 Hz
|
||||
- High frequency raw imu data transmission
|
||||
- Joystick support
|
||||
- Support sending waypoints to Copter and Rover
|
||||
- Remove the XML refs file in favor of binary entity creation
|
||||
|
||||
16) Safety related enhancements and fixes
|
||||
|
||||
- Accel/Gyro inconsistent message fixed for using with only single IMU
|
||||
- Battery monitor failure reported to GCS, triggers battery failsafe but does not take action
|
||||
- Far from EKF origin pre-arm check removed (Copter only)
|
||||
- Fence breach warning message slightly improved
|
||||
- Fence enhancements incluiding alt min fence (Copter only, see FENCE_AUTOENABLE, FENCE_OPTIONS)
|
||||
- Fences can be stored to SD Card (see BRD_SD_FENCE param)
|
||||
- ICEngine stopped when in E-Stop or safety engaged (Plane only)
|
||||
- LEDs flash green lights based on EKF location not GPS
|
||||
- Parachute option to skip disarm before parachute release (see CHUTE_OPTIONS)
|
||||
- Plane FENCE_AUTOENABLE of 1 or 2 deprecation warning added
|
||||
- Pre-arm check if OpenDroneID is compiled in but disabled
|
||||
- Pre-arm check of duplicate RC aux functions fixed (was skipping recently added aux functions)
|
||||
- Pre-arm checks alert user more quickly on failure
|
||||
- Prearm check for misconfigured EAHRS_SENSORS and GPS_TYPE
|
||||
- Proximity sensor based avoidance keeps working even if one proximity sensor fails (Copter, Rover)
|
||||
- RC aux functions for Arm, Disarm, E-Stop and Parachute ignored when RC is first turned on
|
||||
- Warning of duplicate SERIALx_PROTOCOL = RCIN
|
||||
|
||||
17) Other bug fixes and minor enhancements
|
||||
|
||||
- Accel cal fixed for auxiliary IMUs (e.g. IMU4 and higher)
|
||||
- Bootloader fix to reduce unnecessary mass erasing of flash when using STLink or Jlink tools
|
||||
- Bootloader rejects allocation of broadcast node ID
|
||||
- CAN forward registering/de-registering fix (affected Mission Planner DroneCAN UI)
|
||||
- Dijkstras fix to correct use of uninitialised variable
|
||||
- DShot rates are not limited by NeoPixel rates
|
||||
- Ethernet and CAN bootloader fix to prevent getting stuck in bootloader mode
|
||||
- Filesystem does not show entries for empty @ files
|
||||
- Filesystem efficiency improvements when reading files
|
||||
- Flight statistics only reset if user sets STAT_RESET to zero (avoids accidental reset)
|
||||
- Flight time statistics updated on disarm (avoids issue if vehicle powered-down soon after disarm)
|
||||
- Internal error thrown if we lose parameters due to saving queue being too small
|
||||
- MAVLink via DroneCAN baud rate fix
|
||||
- SPI pins may also be used as GPIOs
|
||||
- Terrain cache size configurable (see TERRAIN_CACHE_SZ)
|
||||
|
||||
18) Developer focused fixes and enhancements
|
||||
|
||||
- AP_Camera gets example python code showing how to use GStreamer with UDP and RTSP video streams
|
||||
- Cygwin build fix for non-SITL builds
|
||||
- Cygwin build fixed with malloc wrap
|
||||
- DroneCAN and scripting support FlexDebug messages (see CAN_Dn_UC_OPTION, FlexDebug.lua)
|
||||
- EKF3 code generator documentation and cleanup
|
||||
- GPS jamming simulator added
|
||||
- MacOS compiler warnings reduced
|
||||
- SFML joystick support
|
||||
- SITL support for OpenBSD
|
||||
- Text warning if older Fence or Rally point protocols are used
|
||||
------------------------------------------------------------------
|
||||
Release 4.5.7 08 Oct 2024
|
||||
|
||||
Changes from 4.5.7-beta1
|
||||
|
@ -435,7 +435,7 @@ void Rover::one_second_loop(void)
|
||||
set_control_channels();
|
||||
|
||||
// cope with changes to aux functions
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// update notify flags
|
||||
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
|
||||
|
@ -70,7 +70,7 @@ void Rover::init_ardupilot()
|
||||
|
||||
init_rc_in(); // sets up rc channels deadzone
|
||||
g2.motors.init(get_frame_type()); // init motors including setting servo out channels ranges
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
// init wheel encoders
|
||||
g2.wheel_encoder.init();
|
||||
|
@ -292,13 +292,15 @@ AP_HW_2RAWH743 1173
|
||||
AP_HW_X-MAV-AP-H743V2 1174
|
||||
AP_HW_BETAFPV_F4_2-3S_20A 1175
|
||||
AP_HW_MicoAir743AIOv1 1176
|
||||
|
||||
AP_HW_CrazyF405 1177
|
||||
AP_HW_FlywooF405HD_AIOv2 1180
|
||||
AP_HW_FlywooH743Pro 1181
|
||||
|
||||
AP_HW_ESP32_PERIPH 1205
|
||||
AP_HW_ESP32S3_PERIPH 1206
|
||||
|
||||
AP_HW_CSKY-PMU 1212
|
||||
|
||||
AP_HW_MUPilot 1222
|
||||
|
||||
AP_HW_CBUnmanned-CM405-FC 1301
|
||||
@ -332,8 +334,12 @@ AP_HW_GEPRCF745BTHD 1501
|
||||
|
||||
AP_HW_HGLRCF405V4 1524
|
||||
|
||||
AP_HW_F4BY_F427 1530
|
||||
|
||||
AP_HW_MFT-SEMA100 2000
|
||||
|
||||
AP_HW_AET-H743-Basic 2024
|
||||
|
||||
AP_HW_SakuraRC-H743 2714
|
||||
|
||||
# IDs 4000-4009 reserved for Karshak Drones
|
||||
@ -405,6 +411,12 @@ AP_HW_DroneBuild_G2 5701
|
||||
|
||||
# IDs 6000-6099 reserved for SpektreWorks
|
||||
|
||||
# IDs 6100-6109 reserved for MFE
|
||||
AP_HW_MFE_PDB_CAN 6100
|
||||
AP_HW_MFE_POS3_CAN 6101
|
||||
AP_HW_MFE_RTK_CAN 6102
|
||||
AP_HW_MFE_AirSpeed_CAN 6103
|
||||
|
||||
# IDs 6600-6699 reserved for Eagle Eye Drones
|
||||
|
||||
# IDs 6900-6909 reserved for Easy Aerial
|
||||
|
@ -627,6 +627,7 @@ void AP_Periph_FW::prepare_reboot()
|
||||
*/
|
||||
void AP_Periph_FW::reboot(bool hold_in_bootloader)
|
||||
{
|
||||
prepare_reboot();
|
||||
hal.scheduler->reboot(hold_in_bootloader);
|
||||
}
|
||||
|
||||
|
@ -32,8 +32,10 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
||||
MSG_MCU_STATUS,
|
||||
#endif
|
||||
MSG_MEMINFO,
|
||||
#if AP_GPS_ENABLED
|
||||
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
|
||||
MSG_GPS_RAW,
|
||||
#endif
|
||||
#if AP_GPS_GPS_RTK_SENDING_ENABLED
|
||||
MSG_GPS_RTK,
|
||||
#endif
|
||||
};
|
||||
|
@ -41,6 +41,7 @@ protected:
|
||||
|
||||
void send_nav_controller_output() const override {};
|
||||
void send_pid_tuning() override {};
|
||||
virtual uint8_t send_available_mode(uint8_t index) const override { return 0; }
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -71,7 +71,7 @@ void AP_Periph_FW::rcout_init()
|
||||
hal.rcout->set_freq(esc_mask, g.esc_rate.get());
|
||||
|
||||
// setup ESCs with the desired PWM type, allowing for DShot
|
||||
SRV_Channels::init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
|
||||
AP::srv().init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
|
||||
|
||||
// run DShot at 1kHz
|
||||
hal.rcout->set_dshot_rate(SRV_Channels::get_dshot_rate(), 400);
|
||||
@ -83,7 +83,7 @@ void AP_Periph_FW::rcout_init()
|
||||
void AP_Periph_FW::rcout_init_1Hz()
|
||||
{
|
||||
// this runs at 1Hz to allow for run-time param changes
|
||||
SRV_Channels::enable_aux_servos();
|
||||
AP::srv().enable_aux_servos();
|
||||
|
||||
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
|
||||
servo_channels.set_esc_scaling_for(SRV_Channels::get_motor_function(i));
|
||||
@ -156,10 +156,11 @@ void AP_Periph_FW::rcout_update()
|
||||
}
|
||||
rcout_has_new_data_to_update = false;
|
||||
|
||||
auto &srv = AP::srv();
|
||||
SRV_Channels::calc_pwm();
|
||||
SRV_Channels::cork();
|
||||
srv.cork();
|
||||
SRV_Channels::output_ch_all();
|
||||
SRV_Channels::push();
|
||||
srv.push();
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
if (now_ms - last_esc_telem_update_ms >= esc_telem_update_period_ms) {
|
||||
last_esc_telem_update_ms = now_ms;
|
||||
|
@ -82,7 +82,8 @@ def build(bld):
|
||||
'AP_RobotisServo',
|
||||
'AP_FETtecOneWire',
|
||||
'GCS_MAVLink',
|
||||
'AP_Relay'
|
||||
'AP_Relay',
|
||||
'AP_MultiHeap',
|
||||
]
|
||||
|
||||
bld.ap_stlib(
|
||||
|
@ -205,3 +205,4 @@ Naveen Kumar Kilaparthi
|
||||
Amr Attia
|
||||
Alessandro Martini
|
||||
Eren Mert YİĞİT
|
||||
Prashant Powar
|
||||
|
BIN
Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin
generated
Executable file
BIN
Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin
generated
Executable file
Binary file not shown.
BIN
Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin
generated
Executable file
BIN
Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin
generated
Executable file
Binary file not shown.
BIN
Tools/IO_Firmware/iofirmware_cube_highpolh.bin
generated
Executable file
BIN
Tools/IO_Firmware/iofirmware_cube_highpolh.bin
generated
Executable file
Binary file not shown.
BIN
Tools/IO_Firmware/iofirmware_cube_lowpolh.bin
generated
Executable file
BIN
Tools/IO_Firmware/iofirmware_cube_lowpolh.bin
generated
Executable file
Binary file not shown.
@ -128,6 +128,7 @@ COMMON_VEHICLE_DEPENDENT_LIBRARIES = [
|
||||
'AP_Beacon',
|
||||
'AP_Arming',
|
||||
'AP_RCMapper',
|
||||
'AP_MultiHeap',
|
||||
]
|
||||
|
||||
def get_legacy_defines(sketch_name, bld):
|
||||
|
@ -177,7 +177,10 @@ class Board:
|
||||
|
||||
if cfg.options.enable_networking_tests:
|
||||
env.CXXFLAGS += ['-DAP_NETWORKING_TESTS_ENABLED=1']
|
||||
|
||||
|
||||
if cfg.options.enable_iomcu_profiled_support:
|
||||
env.CXXFLAGS += ['-DAP_IOMCU_PROFILED_SUPPORT_ENABLED=1']
|
||||
|
||||
d = env.get_merged_dict()
|
||||
# Always prepend so that arguments passed in the command line get
|
||||
# the priority.
|
||||
@ -696,6 +699,12 @@ class sitl(Board):
|
||||
cfg.define('AP_NOTIFY_LP5562_BUS', 2)
|
||||
cfg.define('AP_NOTIFY_LP5562_ADDR', 0x30)
|
||||
|
||||
# turn on fencepoint and rallypoint protocols so they're still tested:
|
||||
env.CXXFLAGS.extend([
|
||||
'-DAP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED=HAL_GCS_ENABLED&&HAL_RALLY_ENABLED',
|
||||
'-DAC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT=HAL_GCS_ENABLED&&AP_FENCE_ENABLED'
|
||||
])
|
||||
|
||||
try:
|
||||
env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=0')
|
||||
except ValueError:
|
||||
|
@ -552,13 +552,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.start_subtest("Radio failsafe RTL fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 1)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe RTL fails into land mode due to bad position.")
|
||||
|
||||
@ -567,13 +567,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.start_subtest("Radio failsafe SmartRTL->RTL fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 4)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe SmartRTL->RTL fails into land mode due to bad position.")
|
||||
|
||||
@ -582,13 +582,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 5)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe SmartRTL->LAND fails into land mode due to bad position.")
|
||||
|
||||
@ -597,9 +597,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.start_subtest("Radio failsafe SmartRTL->RTL fails into RTL mode due to no path.")
|
||||
self.set_parameter('FS_THR_ENABLE', 4)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
@ -613,9 +613,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to no path.")
|
||||
self.set_parameter('FS_THR_ENABLE', 5)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
@ -1958,8 +1958,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
glitch_current = 0
|
||||
self.progress("Apply first glitch")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# record position for 30 seconds
|
||||
@ -1973,15 +1973,15 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
glitch_current = -1
|
||||
self.progress("Completed Glitches")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
else:
|
||||
self.progress("Applying glitch %u" % glitch_current)
|
||||
# move onto the next glitch
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# start displaying distance moved after all glitches applied
|
||||
@ -2002,8 +2002,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
# disable gps glitch
|
||||
if glitch_current != -1:
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
if self.use_map:
|
||||
self.show_gps_and_sim_positions(False)
|
||||
@ -2024,7 +2024,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=1)
|
||||
|
||||
# apply glitch
|
||||
self.set_parameter("SIM_GPS_GLITCH_X", 0.001)
|
||||
self.set_parameter("SIM_GPS1_GLTCH_X", 0.001)
|
||||
|
||||
# check lean angles remain stable for 20 seconds
|
||||
tstart = self.get_sim_time()
|
||||
@ -2098,11 +2098,11 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
# stop and test loss of GPS for a short time - it should resume GPS use without falling back into a non aiding mode
|
||||
self.change_mode("LOITER")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 0,
|
||||
"SIM_GPS1_ENABLE": 1,
|
||||
})
|
||||
# regaining GPS should not result in it falling back to a non-navigation mode
|
||||
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=1)
|
||||
@ -2118,8 +2118,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
glitch_current = 0
|
||||
self.progress("Apply first glitch")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# record position for 30 seconds
|
||||
@ -2132,15 +2132,15 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
if glitch_current < glitch_num:
|
||||
self.progress("Applying glitch %u" % glitch_current)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# turn off glitching
|
||||
self.progress("Completed Glitches")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
|
||||
# continue with the mission
|
||||
@ -2526,7 +2526,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.set_parameters({
|
||||
"SIM_FLOW_ENABLE": 1,
|
||||
"FLOW_TYPE": 10,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
"SIM_TERRAIN": 0,
|
||||
})
|
||||
|
||||
@ -2980,13 +2980,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
'''fly a mission far from the vehicle origin'''
|
||||
# Fly mission #1
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
nz = mavutil.location(-43.730171, 169.983118, 1466.3, 270)
|
||||
self.set_origin(nz)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 0,
|
||||
"SIM_GPS1_ENABLE": 1,
|
||||
})
|
||||
self.progress("# Load copter_mission")
|
||||
# load the waypoint count
|
||||
@ -3028,8 +3028,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"GPS1_TYPE": 9,
|
||||
"GPS2_TYPE": 9,
|
||||
# disable simulated GPS, so only via DroneCAN
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS2_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 0,
|
||||
# this ensures we use DroneCAN baro and compass
|
||||
"SIM_BARO_COUNT" : 0,
|
||||
"SIM_MAG1_DEVID" : 0,
|
||||
@ -3206,7 +3206,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"EK3_SRC1_POSZ": 3,
|
||||
"EK3_AFFINITY" : 1,
|
||||
"GPS2_TYPE" : 1,
|
||||
"SIM_GPS2_DISABLE" : 0,
|
||||
"SIM_GPS2_ENABLE" : 1,
|
||||
"SIM_GPS2_GLTCH_Z" : -30
|
||||
})
|
||||
self.reboot_sitl()
|
||||
@ -7245,7 +7245,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"GPS1_TYPE": 2,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
# if there is no GPS at all then we must direct EK3 to not use
|
||||
# it at all. Otherwise it will never initialise, as it wants
|
||||
@ -8986,7 +8986,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"RNGFND1_POS_Y": -0.07,
|
||||
"RNGFND1_POS_Z": -0.005,
|
||||
"SIM_SONAR_SCALE": 30,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
@ -9045,7 +9045,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.set_parameters({
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
@ -9111,16 +9111,14 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
'''Test GPS Blending'''
|
||||
'''ensure we get dataflash log messages for blended instance'''
|
||||
|
||||
self.context_push()
|
||||
|
||||
# configure:
|
||||
self.set_parameters({
|
||||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
@ -9165,8 +9163,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
raise NotAchievedException("Blended diverged")
|
||||
current_ts = None
|
||||
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
if len(measurements) != 3:
|
||||
raise NotAchievedException("Did not see three GPS measurements!")
|
||||
|
||||
def GPSWeightedBlending(self):
|
||||
'''Test GPS Weighted Blending'''
|
||||
@ -9178,9 +9176,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
@ -9188,8 +9186,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
# configure velocity errors such that the 1st GPS should be
|
||||
# 4/5, second GPS 1/5 of result (0.5**2)/((0.5**2)+(1.0**2))
|
||||
self.set_parameters({
|
||||
"SIM_GPS_VERR_X": 0.3, # m/s
|
||||
"SIM_GPS_VERR_Y": 0.4,
|
||||
"SIM_GPS1_VERR_X": 0.3, # m/s
|
||||
"SIM_GPS1_VERR_Y": 0.4,
|
||||
"SIM_GPS2_VERR_X": 0.6, # m/s
|
||||
"SIM_GPS2_VERR_Y": 0.8,
|
||||
"GPS_BLEND_MASK": 4, # use only speed for blend calculations
|
||||
@ -9245,9 +9243,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
@ -9832,28 +9830,15 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
|
||||
def GPSForYaw(self):
|
||||
'''Moving baseline GPS yaw'''
|
||||
self.context_push()
|
||||
self.load_default_params_file("copter-gps-for-yaw.parm")
|
||||
self.reboot_sitl()
|
||||
ex = None
|
||||
try:
|
||||
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
|
||||
m = self.assert_receive_message("GPS2_RAW")
|
||||
self.progress(self.dump_message_verbose(m))
|
||||
want = 27000
|
||||
if abs(m.yaw - want) > 500:
|
||||
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
|
||||
self.wait_ready_to_arm()
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
||||
self.context_pop()
|
||||
|
||||
self.reboot_sitl()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
|
||||
m = self.assert_receive_message("GPS2_RAW", very_verbose=True)
|
||||
want = 27000
|
||||
if abs(m.yaw - want) > 500:
|
||||
raise NotAchievedException("Expected to get GPS-from-yaw (want %f got %f)" % (want, m.yaw))
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
def SMART_RTL_EnterLeave(self):
|
||||
'''check SmartRTL behaviour when entering/leaving'''
|
||||
@ -11754,7 +11739,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
'''ensure Guided acts appropriately when force-armed'''
|
||||
self.set_parameters({
|
||||
"EK3_SRC2_VELXY": 5,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.load_default_params_file("copter-optflow.parm")
|
||||
self.reboot_sitl()
|
||||
@ -11941,7 +11926,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
'''check FlightOption::REQUIRE_POSITION_FOR_ARMING works'''
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"SIM_GPS_NUMSATS": 3, # EKF does not like < 6
|
||||
"SIM_GPS1_NUMSATS": 3, # EKF does not like < 6
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.change_mode('STABILIZE')
|
||||
@ -12142,7 +12127,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
|
||||
# switch to EKF3
|
||||
self.set_parameters({
|
||||
'SIM_GPS_GLITCH_X' : 0.001, # about 100m
|
||||
'SIM_GPS1_GLTCH_X' : 0.001, # about 100m
|
||||
'EK3_CHECK_SCALE' : 100,
|
||||
'AHRS_EKF_TYPE' : 3})
|
||||
|
||||
|
@ -185,7 +185,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
def NeedEKFToArm(self):
|
||||
"""Ensure the EKF must be healthy for the vehicle to arm."""
|
||||
self.progress("Ensuring we need EKF to be healthy to arm")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.context_collect("STATUSTEXT")
|
||||
tstart = self.get_sim_time()
|
||||
success = False
|
||||
@ -201,7 +201,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
except AutoTestTimeoutException:
|
||||
pass
|
||||
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
def fly_LOITER(self, num_circles=4):
|
||||
@ -2046,14 +2046,14 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.delay_sim_time(60)
|
||||
else:
|
||||
self.delay_sim_time(20)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.progress("Continue orbit without GPS")
|
||||
self.delay_sim_time(20)
|
||||
self.change_mode("RTL")
|
||||
self.wait_distance_to_home(100, 200, timeout=200)
|
||||
# go into LOITER to create additonal time for a GPS re-enable test
|
||||
self.change_mode("LOITER")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
t_enabled = self.get_sim_time()
|
||||
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
|
||||
# to prevent bad GPS being used when coming back after loss of lock due to interence.
|
||||
@ -2064,9 +2064,9 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.delay_sim_time(20)
|
||||
|
||||
self.set_parameter("AHRS_OPTIONS", 1)
|
||||
self.set_parameter("SIM_GPS_JAM", 1)
|
||||
self.set_parameter("SIM_GPS1_JAM", 1)
|
||||
self.delay_sim_time(10)
|
||||
self.set_parameter("SIM_GPS_JAM", 0)
|
||||
self.set_parameter("SIM_GPS1_JAM", 0)
|
||||
t_enabled = self.get_sim_time()
|
||||
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
|
||||
# to prevent bad GPS being used when coming back after loss of lock due to interence.
|
||||
@ -3325,7 +3325,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
"EK3_AFFINITY": 15, # enable affinity for all sensors
|
||||
"EK3_IMU_MASK": 3, # use only 2 IMUs
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_BARO_COUNT": 2,
|
||||
"SIM_BAR2_DISABLE": 0,
|
||||
"ARSPD2_TYPE": 2,
|
||||
@ -3400,9 +3400,9 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
# noise on each axis
|
||||
def sim_gps_verr():
|
||||
self.set_parameters({
|
||||
"SIM_GPS_VERR_X": self.get_parameter("SIM_GPS_VERR_X") + 2,
|
||||
"SIM_GPS_VERR_Y": self.get_parameter("SIM_GPS_VERR_Y") + 2,
|
||||
"SIM_GPS_VERR_Z": self.get_parameter("SIM_GPS_VERR_Z") + 2,
|
||||
"SIM_GPS1_VERR_X": self.get_parameter("SIM_GPS1_VERR_X") + 2,
|
||||
"SIM_GPS1_VERR_Y": self.get_parameter("SIM_GPS1_VERR_Y") + 2,
|
||||
"SIM_GPS1_VERR_Z": self.get_parameter("SIM_GPS1_VERR_Z") + 2,
|
||||
})
|
||||
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True)
|
||||
if self.lane_switches != [1, 0, 1]:
|
||||
@ -4831,6 +4831,34 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def TakeoffIdleThrottle(self):
|
||||
'''Apply idle throttle before takeoff.'''
|
||||
self.customise_SITL_commandline(
|
||||
[],
|
||||
model='plane-catapult',
|
||||
defaults_filepath=self.model_defaults_filepath("plane")
|
||||
)
|
||||
self.set_parameters({
|
||||
"TKOFF_THR_IDLE": 20.0,
|
||||
"TKOFF_THR_MINSPD": 3.0,
|
||||
})
|
||||
self.change_mode("TAKEOFF")
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
# Ensure that the throttle rises to idle throttle.
|
||||
expected_idle_throttle = 1000+10*self.get_parameter("TKOFF_THR_IDLE")
|
||||
self.assert_servo_channel_range(3, expected_idle_throttle-10, expected_idle_throttle+10)
|
||||
|
||||
# Launch the catapult
|
||||
self.set_servo(6, 1000)
|
||||
|
||||
self.delay_sim_time(5)
|
||||
self.change_mode('RTL')
|
||||
|
||||
self.fly_home_land_and_disarm()
|
||||
|
||||
def DCMFallback(self):
|
||||
'''Really annoy the EKF and force fallback'''
|
||||
self.reboot_sitl()
|
||||
@ -4842,8 +4870,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.set_parameters({
|
||||
"EK3_POS_I_GATE": 0,
|
||||
"SIM_GPS_HZ": 1,
|
||||
"SIM_GPS_LAG_MS": 1000,
|
||||
"SIM_GPS1_HZ": 1,
|
||||
"SIM_GPS1_LAG_MS": 1000,
|
||||
})
|
||||
self.wait_statustext("DCM Active", check_context=True, timeout=60)
|
||||
self.wait_statustext("EKF3 Active", check_context=True)
|
||||
@ -5502,8 +5530,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
def AltResetBadGPS(self):
|
||||
'''Tests the handling of poor GPS lock pre-arm alt resets'''
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_Z": 0,
|
||||
"SIM_GPS_ACC": 0.3,
|
||||
"SIM_GPS1_GLTCH_Z": 0,
|
||||
"SIM_GPS1_ACC": 0.3,
|
||||
})
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
@ -5513,8 +5541,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
raise NotAchievedException("Bad relative alt %.1f" % relalt)
|
||||
|
||||
self.progress("Setting low accuracy, glitching GPS")
|
||||
self.set_parameter("SIM_GPS_ACC", 40)
|
||||
self.set_parameter("SIM_GPS_GLITCH_Z", -47)
|
||||
self.set_parameter("SIM_GPS1_ACC", 40)
|
||||
self.set_parameter("SIM_GPS1_GLTCH_Z", -47)
|
||||
|
||||
self.progress("Waiting 10s for height update")
|
||||
self.delay_sim_time(10)
|
||||
@ -6091,7 +6119,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.takeoff(50)
|
||||
self.change_mode('GUIDED')
|
||||
self.context_push()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(30)
|
||||
self.set_attitude_target()
|
||||
self.context_pop()
|
||||
@ -6168,7 +6196,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
|
||||
def ForceArm(self):
|
||||
'''check force-arming functionality'''
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
# 21196 is the mavlink standard, 2989 is legacy
|
||||
for magic_value in 21196, 2989:
|
||||
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK,
|
||||
@ -6389,6 +6417,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.TakeoffTakeoff3,
|
||||
self.TakeoffTakeoff4,
|
||||
self.TakeoffGround,
|
||||
self.TakeoffIdleThrottle,
|
||||
self.ForcedDCM,
|
||||
self.DCMFallback,
|
||||
self.MAVFTP,
|
||||
|
@ -18,7 +18,7 @@ WPNAV_SPEED_DN 300
|
||||
WPNAV_SPEED 2000
|
||||
RTL_ALT 2500
|
||||
ANGLE_MAX 3000
|
||||
SIM_GPS_LAG_MS 0
|
||||
SIM_GPS1_LAG_MS 0
|
||||
GPS_DELAY_MS 20
|
||||
INS_GYRO_FILTER 50
|
||||
INS_ACCEL_FILTER 50
|
||||
|
@ -1,5 +1,5 @@
|
||||
# SITL GPS-for-yaw using a single simulated NMEA GPS
|
||||
EK3_SRC1_YAW 2
|
||||
GPS1_TYPE 5
|
||||
SIM_GPS_TYPE 5
|
||||
SIM_GPS_HDG 1
|
||||
SIM_GPS1_TYPE 5
|
||||
SIM_GPS1_HDG 1
|
||||
|
@ -5,7 +5,8 @@ GPS1_TYPE 17
|
||||
GPS2_TYPE 18
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS1_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
SIM_GPS2_ENABLE 1
|
||||
SIM_GPS2_HDG 1
|
||||
SIM_GPS1_HDG 4
|
||||
|
@ -5,7 +5,8 @@ GPS1_TYPE 17
|
||||
GPS2_TYPE 18
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS1_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
SIM_GPS2_ENABLE 1
|
||||
SIM_GPS2_HDG 1
|
||||
SIM_GPS1_HDG 4
|
||||
|
@ -628,19 +628,12 @@ SIM_FLOW_POS_X,0
|
||||
SIM_FLOW_POS_Y,0
|
||||
SIM_FLOW_POS_Z,0
|
||||
SIM_FLOW_RATE,10
|
||||
SIM_GP2_GLITCH_X,0
|
||||
SIM_GP2_GLITCH_Y,0
|
||||
SIM_GP2_GLITCH_Z,0
|
||||
SIM_GPS_BYTELOSS,0
|
||||
SIM_GPS_DISABLE,0
|
||||
SIM_GPS_DRIFTALT,0
|
||||
SIM_GPS_GLITCH_X,0
|
||||
SIM_GPS_GLITCH_Y,0
|
||||
SIM_GPS_GLITCH_Z,0
|
||||
SIM_GPS_HZ,5
|
||||
SIM_GPS_NOISE,0
|
||||
SIM_GPS_NUMSATS,10
|
||||
SIM_GPS_TYPE,1
|
||||
SIM_GPS1_BYTELOSS,0
|
||||
SIM_GPS1_DRIFTALT,0
|
||||
SIM_GPS1_HZ,5
|
||||
SIM_GPS1_NOISE,0
|
||||
SIM_GPS1_NUMSATS,10
|
||||
SIM_GPS1_TYPE,1
|
||||
SIM_GPS2_ENABLE,0
|
||||
SIM_IMU_POS_X,0
|
||||
SIM_IMU_POS_Y,0
|
||||
|
@ -182,7 +182,7 @@ class LoggerDocco(object):
|
||||
return
|
||||
# Make sure lengths match up
|
||||
if len(fmts) != len(self.fields_order):
|
||||
print(f"Number of fmts don't match fields: msg={self.name} fmts={fmts} num_fields={len(self.fields_order)}")
|
||||
print(f"Number of fmts don't match fields: msg={self.name} fmts={fmts} num_fields={len(self.fields_order)} {self.fields_order}") # noqa:E501
|
||||
return
|
||||
# Loop through the list
|
||||
for idx in range(0, len(fmts)):
|
||||
|
@ -1764,8 +1764,8 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
||||
|
||||
# Kill any GPSs
|
||||
self.set_parameters({
|
||||
'SIM_GPS_DISABLE': 1,
|
||||
'SIM_GPS2_DISABLE': 1,
|
||||
'SIM_GPS1_ENABLE': 0,
|
||||
'SIM_GPS2_ENABLE': 0,
|
||||
})
|
||||
self.delay_sim_time(5)
|
||||
|
||||
|
@ -6807,7 +6807,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
'''Test jamming simulation works'''
|
||||
self.wait_ready_to_arm()
|
||||
start_loc = self.assert_receive_message('GPS_RAW_INT')
|
||||
self.set_parameter("SIM_GPS_JAM", 1)
|
||||
self.set_parameter("SIM_GPS1_JAM", 1)
|
||||
|
||||
class Requirement():
|
||||
def __init__(self, field, min_value):
|
||||
|
@ -258,7 +258,6 @@ class TestBuildOptions(object):
|
||||
'AP_COMPASS_MAG3110_ENABLED', # must be in hwdef, not probed
|
||||
'AP_COMPASS_MMC5XX3_ENABLED', # must be in hwdef, not probed
|
||||
'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', # completely elided
|
||||
'AP_MAVLINK_MSG_HIL_GPS_ENABLED', # no symbol available
|
||||
'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', # no symbol available
|
||||
'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', # no symbol available
|
||||
'HAL_MSP_SENSORS_ENABLED', # no symbol available
|
||||
|
@ -2711,8 +2711,6 @@ class TestSuite(ABC):
|
||||
"SIM_MAG1_OFS_Z",
|
||||
"SIM_PARA_ENABLE",
|
||||
"SIM_PARA_PIN",
|
||||
"SIM_PLD_ALT_LMT",
|
||||
"SIM_PLD_DIST_LMT",
|
||||
"SIM_RICH_CTRL",
|
||||
"SIM_RICH_ENABLE",
|
||||
"SIM_SHIP_DSIZE",
|
||||
@ -3665,7 +3663,7 @@ class TestSuite(ABC):
|
||||
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:
|
||||
raise NotAchievedException("Expected GPS to be OK")
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)
|
||||
self.set_parameter("SIM_GPS_TYPE", 0)
|
||||
self.set_parameter("SIM_GPS1_TYPE", 0)
|
||||
self.delay_sim_time(10)
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
@ -3674,7 +3672,7 @@ class TestSuite(ABC):
|
||||
raise NotAchievedException("Expected GPS to be failed")
|
||||
|
||||
self.start_subtest("HIGH_LATENCY2 location")
|
||||
self.set_parameter("SIM_GPS_TYPE", 1)
|
||||
self.set_parameter("SIM_GPS1_TYPE", 1)
|
||||
self.delay_sim_time(10)
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
self.progress(self.dump_message_verbose(m))
|
||||
@ -8471,7 +8469,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):
|
||||
"""Disable GPS and wait for EKF to report the end of assistance from GPS."""
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
tstart = self.get_sim_time()
|
||||
|
||||
""" if using SITL estimates directly """
|
||||
@ -10683,7 +10681,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.wait_ekf_happy() # EKF may stay unhappy for a while
|
||||
self.progress("PASS not able to arm without Position in mode : %s" % mode)
|
||||
if mode in self.get_no_position_not_settable_modes_list():
|
||||
@ -10693,10 +10691,10 @@ Also, ignores heartbeats not from our target system'''
|
||||
try:
|
||||
self.change_mode(mode, timeout=15)
|
||||
except AutoTestTimeoutException:
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.progress("PASS not able to set mode without Position : %s" % mode)
|
||||
except ValueError:
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.progress("PASS not able to set mode without Position : %s" % mode)
|
||||
if mode == "FOLLOW":
|
||||
self.set_parameter("FOLL_ENABLE", 0)
|
||||
@ -12313,6 +12311,7 @@ switch value'''
|
||||
expected_count = 0
|
||||
seen_ids = {}
|
||||
self.progress("Downloading parameters")
|
||||
debug = False
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if not start_done or now - last_parameter_received > 10:
|
||||
@ -12323,6 +12322,7 @@ switch value'''
|
||||
elif attempt_count != 0:
|
||||
self.progress("Download failed; retrying")
|
||||
self.delay_sim_time(1)
|
||||
debug = True
|
||||
self.drain_mav()
|
||||
self.mav.mav.param_request_list_send(target_system, target_component)
|
||||
attempt_count += 1
|
||||
@ -12337,8 +12337,8 @@ switch value'''
|
||||
if m.param_index == 65535:
|
||||
self.progress("volunteered parameter: %s" % str(m))
|
||||
continue
|
||||
if False:
|
||||
self.progress(" received (%4u/%4u %s=%f" %
|
||||
if debug:
|
||||
self.progress(" received id=%4u param_count=%4u %s=%f" %
|
||||
(m.param_index, m.param_count, m.param_id, m.param_value))
|
||||
if m.param_index >= m.param_count:
|
||||
raise ValueError("parameter index (%u) gte parameter count (%u)" %
|
||||
@ -12531,7 +12531,7 @@ switch value'''
|
||||
self.context_collect("STATUSTEXT")
|
||||
self.set_parameters({
|
||||
"AFS_MAX_GPS_LOSS": 1,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.wait_statustext("AFS State: GPS_LOSS", check_context=True)
|
||||
self.context_pop()
|
||||
@ -14160,7 +14160,7 @@ switch value'''
|
||||
self.context_collect("STATUSTEXT")
|
||||
for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:
|
||||
self.start_subtest("Checking GPS type %s" % name)
|
||||
self.set_parameter("SIM_GPS_TYPE", sim_gps_type)
|
||||
self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)
|
||||
self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)
|
||||
if gps_type is None:
|
||||
gps_type = 1 # auto-detect
|
||||
@ -14265,7 +14265,7 @@ switch value'''
|
||||
|
||||
self.start_subtest("Ensure detection when sim gps connected")
|
||||
self.set_parameter("SIM_GPS2_TYPE", 1)
|
||||
self.set_parameter("SIM_GPS2_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS2_ENABLE", 1)
|
||||
# a reboot is required after setting GPS2_TYPE. We start
|
||||
# sending GPS2_RAW out, once the parameter is set, but a
|
||||
# reboot is required because _port[1] is only set in
|
||||
@ -14281,9 +14281,9 @@ switch value'''
|
||||
raise NotAchievedException("Incorrect fix type")
|
||||
|
||||
self.start_subtest("Check parameters are per-GPS")
|
||||
self.assert_parameter_value("SIM_GPS_NUMSATS", 10)
|
||||
self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)
|
||||
self.assert_gps_satellite_count("GPS_RAW_INT", 10)
|
||||
self.set_parameter("SIM_GPS_NUMSATS", 13)
|
||||
self.set_parameter("SIM_GPS1_NUMSATS", 13)
|
||||
self.assert_gps_satellite_count("GPS_RAW_INT", 13)
|
||||
|
||||
self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)
|
||||
@ -14311,7 +14311,7 @@ switch value'''
|
||||
if abs(gpi_alt - new_gpi_alt) > 100:
|
||||
raise NotAchievedException("alt moved unexpectedly")
|
||||
self.progress("Killing first GPS")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.delay_sim_time(1)
|
||||
self.progress("Checking altitude now matches second GPS")
|
||||
m = self.assert_receive_message("GLOBAL_POSITION_INT")
|
||||
|
BIN
Tools/bootloaders/AET-H743-Basic_bl.bin
generated
Normal file
BIN
Tools/bootloaders/AET-H743-Basic_bl.bin
generated
Normal file
Binary file not shown.
BIN
Tools/bootloaders/AET-H743-Basic_bl.hex
generated
Normal file
BIN
Tools/bootloaders/AET-H743-Basic_bl.hex
generated
Normal file
Binary file not shown.
BIN
Tools/bootloaders/F4BY_F427_bl.bin
generated
Executable file
BIN
Tools/bootloaders/F4BY_F427_bl.bin
generated
Executable file
Binary file not shown.
BIN
Tools/bootloaders/MFE_POS3_CAN_bl.bin
generated
Normal file
BIN
Tools/bootloaders/MFE_POS3_CAN_bl.bin
generated
Normal file
Binary file not shown.
180
Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/copter_takeoff.py
Executable file
180
Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/copter_takeoff.py
Executable file
@ -0,0 +1,180 @@
|
||||
#!/usr/bin/env python3
|
||||
# Copyright 2023 ArduPilot.org.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License
|
||||
# along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
|
||||
"""
|
||||
Run takeoff test on Copter.
|
||||
|
||||
Warning - This is NOT production code; it's a simple demo of capability.
|
||||
"""
|
||||
|
||||
import math
|
||||
import rclpy
|
||||
import time
|
||||
import errno
|
||||
|
||||
from rclpy.node import Node
|
||||
from builtin_interfaces.msg import Time
|
||||
from ardupilot_msgs.msg import GlobalPosition
|
||||
from geographic_msgs.msg import GeoPoseStamped
|
||||
from geopy import distance
|
||||
from geopy import point
|
||||
from ardupilot_msgs.srv import ArmMotors
|
||||
from ardupilot_msgs.srv import ModeSwitch
|
||||
from ardupilot_msgs.srv import Takeoff
|
||||
|
||||
|
||||
|
||||
COPTER_MODE_GUIDED = 4
|
||||
|
||||
TAKEOFF_ALT = 10.5
|
||||
|
||||
class CopterTakeoff(Node):
|
||||
"""Copter takeoff using guided control."""
|
||||
|
||||
def __init__(self):
|
||||
"""Initialise the node."""
|
||||
super().__init__("copter_takeoff")
|
||||
|
||||
self.declare_parameter("arm_topic", "/ap/arm_motors")
|
||||
self._arm_topic = self.get_parameter("arm_topic").get_parameter_value().string_value
|
||||
self._client_arm = self.create_client(ArmMotors, self._arm_topic)
|
||||
while not self._client_arm.wait_for_service(timeout_sec=1.0):
|
||||
self.get_logger().info('arm service not available, waiting again...')
|
||||
|
||||
self.declare_parameter("mode_topic", "/ap/mode_switch")
|
||||
self._mode_topic = self.get_parameter("mode_topic").get_parameter_value().string_value
|
||||
self._client_mode_switch = self.create_client(ModeSwitch, self._mode_topic)
|
||||
while not self._client_mode_switch.wait_for_service(timeout_sec=1.0):
|
||||
self.get_logger().info('mode switch service not available, waiting again...')
|
||||
|
||||
self.declare_parameter("takeoff_service", "/ap/experimental/takeoff")
|
||||
self._takeoff_topic = self.get_parameter("takeoff_service").get_parameter_value().string_value
|
||||
self._client_takeoff = self.create_client(Takeoff, self._takeoff_topic)
|
||||
while not self._client_takeoff.wait_for_service(timeout_sec=1.0):
|
||||
self.get_logger().info('takeoff service not available, waiting again...')
|
||||
|
||||
self.declare_parameter("geopose_topic", "/ap/geopose/filtered")
|
||||
self._geopose_topic = self.get_parameter("geopose_topic").get_parameter_value().string_value
|
||||
qos = rclpy.qos.QoSProfile(
|
||||
reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT, durability=rclpy.qos.DurabilityPolicy.VOLATILE, depth=1
|
||||
)
|
||||
|
||||
self._subscription_geopose = self.create_subscription(GeoPoseStamped, self._geopose_topic, self.geopose_cb, qos)
|
||||
self._cur_geopose = GeoPoseStamped()
|
||||
|
||||
def geopose_cb(self, msg: GeoPoseStamped):
|
||||
"""Process a GeoPose message."""
|
||||
stamp = msg.header.stamp
|
||||
if stamp.sec:
|
||||
self.get_logger().info("From AP : Geopose [sec:{}, nsec: {}]".format(stamp.sec, stamp.nanosec))
|
||||
|
||||
# Store current state
|
||||
self._cur_geopose = msg
|
||||
|
||||
|
||||
def arm(self):
|
||||
req = ArmMotors.Request()
|
||||
req.arm = True
|
||||
future = self._client_arm.call_async(req)
|
||||
rclpy.spin_until_future_complete(self, future)
|
||||
return future.result()
|
||||
|
||||
def arm_with_timeout(self, timeout: rclpy.duration.Duration):
|
||||
"""Try to arm. Returns true on success, or false if arming fails or times out."""
|
||||
armed = False
|
||||
start = self.get_clock().now()
|
||||
while not armed and self.get_clock().now() - start < timeout:
|
||||
armed = self.arm().result
|
||||
time.sleep(1)
|
||||
return armed
|
||||
|
||||
def switch_mode(self, mode):
|
||||
req = ModeSwitch.Request()
|
||||
assert mode in [COPTER_MODE_GUIDED]
|
||||
req.mode = mode
|
||||
future = self._client_mode_switch.call_async(req)
|
||||
rclpy.spin_until_future_complete(self, future)
|
||||
return future.result()
|
||||
|
||||
def switch_mode_with_timeout(self, desired_mode: int, timeout: rclpy.duration.Duration):
|
||||
"""Try to switch mode. Returns true on success, or false if mode switch fails or times out."""
|
||||
is_in_desired_mode = False
|
||||
start = self.get_clock().now()
|
||||
while not is_in_desired_mode:
|
||||
result = self.switch_mode(desired_mode)
|
||||
# Handle successful switch or the case that the vehicle is already in expected mode
|
||||
is_in_desired_mode = result.status or result.curr_mode == desired_mode
|
||||
time.sleep(1)
|
||||
|
||||
return is_in_desired_mode
|
||||
|
||||
def takeoff(self, alt):
|
||||
req = Takeoff.Request()
|
||||
req.alt = alt
|
||||
future = self._client_takeoff.call_async(req)
|
||||
rclpy.spin_until_future_complete(self, future)
|
||||
return future.result()
|
||||
|
||||
def takeoff_with_timeout(self, alt: int, timeout: rclpy.duration.Duration):
|
||||
"""Try to takeoff. Returns true on success, or false if takeoff fails or times out."""
|
||||
takeoff_success = False
|
||||
start = self.get_clock().now()
|
||||
while not takeoff_success:
|
||||
result = self.takeoff(alt)
|
||||
takeoff_success = result.status
|
||||
time.sleep(1)
|
||||
|
||||
return takeoff_success
|
||||
|
||||
def get_cur_geopose(self):
|
||||
"""Return latest geopose."""
|
||||
return self._cur_geopose
|
||||
|
||||
def main(args=None):
|
||||
"""Node entry point."""
|
||||
rclpy.init(args=args)
|
||||
node = CopterTakeoff()
|
||||
try:
|
||||
if not node.switch_mode_with_timeout(COPTER_MODE_GUIDED, rclpy.duration.Duration(seconds=20)):
|
||||
raise RuntimeError("Unable to switch to guided mode")
|
||||
# Block till armed, which will wait for EKF3 to initialize
|
||||
if not node.arm_with_timeout(rclpy.duration.Duration(seconds=30)):
|
||||
raise RuntimeError("Unable to arm")
|
||||
|
||||
# Block till in takeoff
|
||||
if not node.takeoff_with_timeout(TAKEOFF_ALT, rclpy.duration.Duration(seconds=20)):
|
||||
raise RuntimeError("Unable to takeoff")
|
||||
|
||||
is_ascending_to_takeoff_alt = True
|
||||
while is_ascending_to_takeoff_alt:
|
||||
rclpy.spin_once(node)
|
||||
time.sleep(1.0)
|
||||
|
||||
is_ascending_to_takeoff_alt = node.get_cur_geopose().pose.position.altitude < TAKEOFF_ALT
|
||||
|
||||
if is_ascending_to_takeoff_alt:
|
||||
raise RuntimeError("Failed to reach takeoff altitude")
|
||||
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
|
||||
# Destroy the node explicitly.
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -33,6 +33,7 @@ from geopy import distance
|
||||
from geopy import point
|
||||
from ardupilot_msgs.srv import ArmMotors
|
||||
from ardupilot_msgs.srv import ModeSwitch
|
||||
from geographic_msgs.msg import GeoPointStamped
|
||||
|
||||
|
||||
PLANE_MODE_TAKEOFF = 13
|
||||
@ -78,6 +79,15 @@ class PlaneWaypointFollower(Node):
|
||||
|
||||
self._subscription_geopose = self.create_subscription(GeoPoseStamped, self._geopose_topic, self.geopose_cb, qos)
|
||||
self._cur_geopose = GeoPoseStamped()
|
||||
|
||||
self.declare_parameter("goal_topic", "/ap/goal_lla")
|
||||
self._goal_topic = self.get_parameter("goal_topic").get_parameter_value().string_value
|
||||
qos = rclpy.qos.QoSProfile(
|
||||
reliability=rclpy.qos.ReliabilityPolicy.RELIABLE, durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, depth=1
|
||||
)
|
||||
|
||||
self._subscription_goal = self.create_subscription(GeoPointStamped, self._goal_topic, self.goal_cb, qos)
|
||||
self._cur_goal = GeoPointStamped()
|
||||
|
||||
def geopose_cb(self, msg: GeoPoseStamped):
|
||||
"""Process a GeoPose message."""
|
||||
@ -87,6 +97,15 @@ class PlaneWaypointFollower(Node):
|
||||
|
||||
# Store current state
|
||||
self._cur_geopose = msg
|
||||
|
||||
def goal_cb(self, msg: GeoPointStamped):
|
||||
"""Process a Goal message."""
|
||||
stamp = msg.header.stamp
|
||||
self.get_logger().info("From AP : Goal [sec:{}, nsec: {}, lat:{} lon:{}]"
|
||||
.format(stamp.sec, stamp.nanosec,msg.position.latitude, msg.position.longitude))
|
||||
|
||||
# Store current state
|
||||
self._cur_goal = msg
|
||||
|
||||
def arm(self):
|
||||
req = ArmMotors.Request()
|
||||
@ -127,6 +146,10 @@ class PlaneWaypointFollower(Node):
|
||||
def get_cur_geopose(self):
|
||||
"""Return latest geopose."""
|
||||
return self._cur_geopose
|
||||
|
||||
def get_cur_goal(self):
|
||||
"""Return latest goal."""
|
||||
return self._cur_goal
|
||||
|
||||
def send_goal_position(self, goal_global_pos):
|
||||
"""Send goal position. Must be in guided for this to work."""
|
||||
@ -148,6 +171,15 @@ def achieved_goal(goal_global_pos, cur_geopose):
|
||||
print(f"Goal is {euclidian_distance} meters away")
|
||||
return euclidian_distance < 150
|
||||
|
||||
def going_to_goal(goal_global_pos, cur_goal):
|
||||
p1 = (goal_global_pos.latitude, goal_global_pos.longitude, goal_global_pos.altitude)
|
||||
cur_pos_lla = cur_goal.position
|
||||
p2 = (cur_pos_lla.latitude, cur_pos_lla.longitude, cur_pos_lla.altitude)
|
||||
|
||||
flat_distance = distance.distance(p1[:2], p2[:2]).m
|
||||
euclidian_distance = math.sqrt(flat_distance**2 + (p2[2] - p1[2]) ** 2)
|
||||
print(f"Commanded and received goal are {euclidian_distance} meters away")
|
||||
return euclidian_distance < 1
|
||||
|
||||
def main(args=None):
|
||||
"""Node entry point."""
|
||||
@ -191,11 +223,15 @@ def main(args=None):
|
||||
|
||||
start = node.get_clock().now()
|
||||
has_achieved_goal = False
|
||||
is_going_to_goal = False
|
||||
while not has_achieved_goal and node.get_clock().now() - start < rclpy.duration.Duration(seconds=120):
|
||||
rclpy.spin_once(node)
|
||||
is_going_to_goal = going_to_goal(goal_pos, node.get_cur_goal())
|
||||
has_achieved_goal = achieved_goal(goal_pos, node.get_cur_geopose())
|
||||
time.sleep(1.0)
|
||||
|
||||
if not is_going_to_goal:
|
||||
raise RuntimeError("Unable to go to goal location")
|
||||
if not has_achieved_goal:
|
||||
raise RuntimeError("Unable to achieve goal location")
|
||||
|
||||
|
@ -0,0 +1,78 @@
|
||||
#!/usr/bin/env python3
|
||||
# Copyright 2023 ArduPilot.org.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License
|
||||
# along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
|
||||
"""
|
||||
Run pre_arm check test on Copter.
|
||||
|
||||
Warning - This is NOT production code; it's a simple demo of capability.
|
||||
"""
|
||||
|
||||
import math
|
||||
import rclpy
|
||||
import time
|
||||
import errno
|
||||
|
||||
from rclpy.node import Node
|
||||
from builtin_interfaces.msg import Time
|
||||
from std_srvs.srv import Trigger
|
||||
|
||||
|
||||
class CopterPreArm(Node):
|
||||
"""Check Prearm Service."""
|
||||
|
||||
def __init__(self):
|
||||
"""Initialise the node."""
|
||||
super().__init__("copter_prearm")
|
||||
|
||||
self.declare_parameter("pre_arm_service", "/ap/prearm_check")
|
||||
self._prearm_service = self.get_parameter("pre_arm_service").get_parameter_value().string_value
|
||||
self._client_prearm = self.create_client(Trigger, self._prearm_service)
|
||||
while not self._client_prearm.wait_for_service(timeout_sec=1.0):
|
||||
self.get_logger().info('prearm service not available, waiting again...')
|
||||
|
||||
def prearm(self):
|
||||
req = Trigger.Request()
|
||||
future = self._client_prearm.call_async(req)
|
||||
rclpy.spin_until_future_complete(self, future)
|
||||
return future.result()
|
||||
|
||||
def prearm_with_timeout(self, timeout: rclpy.duration.Duration):
|
||||
"""Check if armable. Returns true on success, or false if arming will fail or times out."""
|
||||
armable = False
|
||||
start = self.get_clock().now()
|
||||
while not armable and self.get_clock().now() - start < timeout:
|
||||
armable = self.prearm().success
|
||||
time.sleep(1)
|
||||
return armable
|
||||
|
||||
def main(args=None):
|
||||
"""Node entry point."""
|
||||
rclpy.init(args=args)
|
||||
node = CopterPreArm()
|
||||
try:
|
||||
# Block till armed, which will wait for EKF3 to initialize
|
||||
if not node.prearm_with_timeout(rclpy.duration.Duration(seconds=30)):
|
||||
raise RuntimeError("Vehicle not armable")
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
|
||||
# Destroy the node explicitly.
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -26,6 +26,8 @@ setup(
|
||||
'console_scripts': [
|
||||
"time_listener = ardupilot_dds_tests.time_listener:main",
|
||||
"plane_waypoint_follower = ardupilot_dds_tests.plane_waypoint_follower:main",
|
||||
"pre_arm_check = ardupilot_dds_tests.pre_arm_check_service:main",
|
||||
"copter_takeoff = ardupilot_dds_tests.copter_takeoff:main",
|
||||
],
|
||||
},
|
||||
)
|
||||
|
@ -0,0 +1,166 @@
|
||||
# Copyright 2023 ArduPilot.org.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# You should have received a copy of the GNU General Public License
|
||||
# along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
|
||||
"""
|
||||
Bring up ArduPilot SITL and check whether the vehicle can be armed.
|
||||
|
||||
colcon test --executor sequential --parallel-workers 0 --base-paths src/ardupilot \
|
||||
--event-handlers=console_cohesion+ --packages-select ardupilot_dds_tests \
|
||||
--pytest-args -k test_prearm_service
|
||||
|
||||
"""
|
||||
|
||||
import launch_pytest
|
||||
import math
|
||||
import time
|
||||
import pytest
|
||||
import rclpy
|
||||
import rclpy.node
|
||||
import threading
|
||||
|
||||
from launch import LaunchDescription
|
||||
|
||||
from launch_pytest.tools import process as process_tools
|
||||
from std_srvs.srv import Trigger
|
||||
|
||||
|
||||
SERVICE = "/ap/prearm_check"
|
||||
|
||||
class PreamService(rclpy.node.Node):
|
||||
def __init__(self):
|
||||
"""Initialise the node."""
|
||||
super().__init__("prearm_client")
|
||||
self.service_available_object = threading.Event()
|
||||
self.is_armable_object = threading.Event()
|
||||
self._client_prearm = self.create_client(Trigger, "/ap/prearm_check")
|
||||
|
||||
def start_node(self):
|
||||
# Add a spin thread.
|
||||
self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,))
|
||||
self.ros_spin_thread.start()
|
||||
|
||||
def prearm_check(self):
|
||||
req = Trigger.Request()
|
||||
future = self._client_prearm.call_async(req)
|
||||
time.sleep(0.2)
|
||||
try:
|
||||
return future.result().success
|
||||
except Exception as e:
|
||||
print(e)
|
||||
return False
|
||||
|
||||
def prearm_with_timeout(self, timeout: rclpy.duration.Duration):
|
||||
result = False
|
||||
start = self.get_clock().now()
|
||||
while not result and self.get_clock().now() - start < timeout:
|
||||
result = self.prearm_check()
|
||||
time.sleep(1)
|
||||
return result
|
||||
|
||||
def process_prearm(self):
|
||||
if self.prearm_with_timeout(rclpy.duration.Duration(seconds=30)):
|
||||
self.is_armable_object.set()
|
||||
|
||||
def start_prearm(self):
|
||||
try:
|
||||
self.prearm_thread.stop()
|
||||
except:
|
||||
print("start_prearm not started yet")
|
||||
self.prearm_thread = threading.Thread(target=self.process_prearm)
|
||||
self.prearm_thread.start()
|
||||
|
||||
|
||||
|
||||
|
||||
@launch_pytest.fixture
|
||||
def launch_sitl_copter_dds_serial(sitl_copter_dds_serial):
|
||||
"""Fixture to create the launch description."""
|
||||
sitl_ld, sitl_actions = sitl_copter_dds_serial
|
||||
|
||||
ld = LaunchDescription(
|
||||
[
|
||||
sitl_ld,
|
||||
launch_pytest.actions.ReadyToTest(),
|
||||
]
|
||||
)
|
||||
actions = sitl_actions
|
||||
yield ld, actions
|
||||
|
||||
|
||||
@launch_pytest.fixture
|
||||
def launch_sitl_copter_dds_udp(sitl_copter_dds_udp):
|
||||
"""Fixture to create the launch description."""
|
||||
sitl_ld, sitl_actions = sitl_copter_dds_udp
|
||||
|
||||
ld = LaunchDescription(
|
||||
[
|
||||
sitl_ld,
|
||||
launch_pytest.actions.ReadyToTest(),
|
||||
]
|
||||
)
|
||||
actions = sitl_actions
|
||||
yield ld, actions
|
||||
|
||||
|
||||
@pytest.mark.launch(fixture=launch_sitl_copter_dds_serial)
|
||||
def test_dds_serial_prearm_service_call(launch_context, launch_sitl_copter_dds_serial):
|
||||
"""Test prearm service AP_DDS."""
|
||||
_, actions = launch_sitl_copter_dds_serial
|
||||
virtual_ports = actions["virtual_ports"].action
|
||||
micro_ros_agent = actions["micro_ros_agent"].action
|
||||
mavproxy = actions["mavproxy"].action
|
||||
sitl = actions["sitl"].action
|
||||
|
||||
# Wait for process to start.
|
||||
process_tools.wait_for_start_sync(launch_context, virtual_ports, timeout=2)
|
||||
process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2)
|
||||
process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2)
|
||||
process_tools.wait_for_start_sync(launch_context, sitl, timeout=2)
|
||||
|
||||
rclpy.init()
|
||||
try:
|
||||
node = PreamService()
|
||||
node.start_node()
|
||||
node.start_prearm()
|
||||
is_armable_flag = node.is_armable_object.wait(timeout=25.0)
|
||||
assert is_armable_flag, f"Vehicle not armable."
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
yield
|
||||
|
||||
|
||||
@pytest.mark.launch(fixture=launch_sitl_copter_dds_udp)
|
||||
def test_dds_udp_prearm_service_call(launch_context, launch_sitl_copter_dds_udp):
|
||||
"""Test prearm service AP_DDS."""
|
||||
_, actions = launch_sitl_copter_dds_udp
|
||||
micro_ros_agent = actions["micro_ros_agent"].action
|
||||
mavproxy = actions["mavproxy"].action
|
||||
sitl = actions["sitl"].action
|
||||
|
||||
# Wait for process to start.
|
||||
process_tools.wait_for_start_sync(launch_context, micro_ros_agent, timeout=2)
|
||||
process_tools.wait_for_start_sync(launch_context, mavproxy, timeout=2)
|
||||
process_tools.wait_for_start_sync(launch_context, sitl, timeout=2)
|
||||
|
||||
rclpy.init()
|
||||
try:
|
||||
node = PreamService()
|
||||
node.start_node()
|
||||
node.start_prearm()
|
||||
is_armable_flag = node.is_armable_object.wait(timeout=25.0)
|
||||
assert is_armable_flag, f"Vehicle not armable."
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
yield
|
@ -17,6 +17,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
|
||||
"msg/Status.msg"
|
||||
"srv/ArmMotors.srv"
|
||||
"srv/ModeSwitch.srv"
|
||||
"srv/Takeoff.srv"
|
||||
DEPENDENCIES geometry_msgs std_msgs
|
||||
ADD_LINTER_TESTS
|
||||
)
|
||||
|
10
Tools/ros2/ardupilot_msgs/srv/Takeoff.srv
Normal file
10
Tools/ros2/ardupilot_msgs/srv/Takeoff.srv
Normal file
@ -0,0 +1,10 @@
|
||||
|
||||
# This service requests the vehicle to takeoff
|
||||
|
||||
# alt : Set the takeoff altitude above home or above terrain(in case of rangefinder)
|
||||
|
||||
float32 alt
|
||||
---
|
||||
# status : True if the request for mode switch was successful, False otherwise
|
||||
|
||||
bool status
|
@ -5,7 +5,13 @@
|
||||
|
||||
XOLDPWD=$PWD # profile changes directory :-(
|
||||
|
||||
. ~/.profile
|
||||
if [ -z "$GITHUB_ACTIONS" ] || [ "$GITHUB_ACTIONS" != "true" ]; then
|
||||
. ~/.profile
|
||||
fi
|
||||
|
||||
if [ "$CI" = "true" ]; then
|
||||
export PIP_ROOT_USER_ACTION=ignore
|
||||
fi
|
||||
|
||||
cd $XOLDPWD
|
||||
|
||||
@ -40,7 +46,7 @@ function install_pymavlink() {
|
||||
if [ $pymavlink_installed -eq 0 ]; then
|
||||
echo "Installing pymavlink"
|
||||
git submodule update --init --recursive --depth 1
|
||||
(cd modules/mavlink/pymavlink && python3 -m pip install --user .)
|
||||
(cd modules/mavlink/pymavlink && python3 -m pip install --progress-bar off --cache-dir /tmp/pip-cache --user .)
|
||||
pymavlink_installed=1
|
||||
fi
|
||||
}
|
||||
@ -51,7 +57,7 @@ function install_mavproxy() {
|
||||
pushd /tmp
|
||||
git clone https://github.com/ardupilot/MAVProxy --depth 1
|
||||
pushd MAVProxy
|
||||
python3 -m pip install --user --force .
|
||||
python3 -m pip install --progress-bar off --cache-dir /tmp/pip-cache --user --force .
|
||||
popd
|
||||
popd
|
||||
mavproxy_installed=1
|
||||
@ -243,6 +249,10 @@ for t in $CI_BUILD_TARGET; do
|
||||
$waf configure --board FreeflyRTK
|
||||
$waf clean
|
||||
$waf AP_Periph
|
||||
echo "Building CubeNode-ETH peripheral fw"
|
||||
$waf configure --board CubeNode-ETH
|
||||
$waf clean
|
||||
$waf AP_Periph
|
||||
continue
|
||||
fi
|
||||
|
||||
@ -454,7 +464,7 @@ for t in $CI_BUILD_TARGET; do
|
||||
echo "Building signed firmwares"
|
||||
sudo apt-get update
|
||||
sudo apt-get install -y python3-dev
|
||||
python3 -m pip install pymonocypher==3.1.3.2
|
||||
python3 -m pip install pymonocypher==3.1.3.2 --progress-bar off --cache-dir /tmp/pip-cache
|
||||
./Tools/scripts/signing/generate_keys.py testkey
|
||||
$waf configure --board CubeOrange-ODID --signed-fw --private-key testkey_private_key.dat
|
||||
$waf copter
|
||||
@ -473,7 +483,11 @@ for t in $CI_BUILD_TARGET; do
|
||||
|
||||
if [ "$t" == "astyle-cleanliness" ]; then
|
||||
echo "Checking AStyle code cleanliness"
|
||||
|
||||
./Tools/scripts/run_astyle.py --dry-run
|
||||
if [ $? -ne 0 ]; then
|
||||
echo The code failed astyle cleanliness checks. Please run ./Tools/scripts/run_astyle.py
|
||||
fi
|
||||
continue
|
||||
fi
|
||||
|
||||
|
@ -29,12 +29,24 @@ run_program(["./waf", "iofirmware"])
|
||||
shutil.copy('build/iomcu/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_lowpolh.bin')
|
||||
shutil.copy('build/iomcu/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_highpolh.bin')
|
||||
|
||||
run_program(["./waf", "configure", "--board", 'iomcu', '--enable-iomcu-profiled-support'])
|
||||
run_program(["./waf", "clean"])
|
||||
run_program(["./waf", "iofirmware"])
|
||||
shutil.copy('build/iomcu/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_lowpolh.bin')
|
||||
shutil.copy('build/iomcu/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_highpolh.bin')
|
||||
|
||||
run_program(["./waf", "configure", "--board", 'iomcu-dshot'])
|
||||
run_program(["./waf", "clean"])
|
||||
run_program(["./waf", "iofirmware"])
|
||||
shutil.copy('build/iomcu-dshot/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin')
|
||||
shutil.copy('build/iomcu-dshot/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_dshot_highpolh.bin')
|
||||
|
||||
run_program(["./waf", "configure", "--board", 'iomcu-dshot', '--enable-iomcu-profiled-support'])
|
||||
run_program(["./waf", "clean"])
|
||||
run_program(["./waf", "iofirmware"])
|
||||
shutil.copy('build/iomcu-dshot/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_dshot_lowpolh.bin')
|
||||
shutil.copy('build/iomcu-dshot/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_cube_dshot_highpolh.bin')
|
||||
|
||||
run_program(["./waf", "configure", "--board", 'iomcu-f103'])
|
||||
run_program(["./waf", "clean"])
|
||||
run_program(["./waf", "iofirmware"])
|
||||
|
@ -364,7 +364,6 @@ BUILD_OPTIONS = [
|
||||
Feature('MAVLink', 'MAVLINK_VERSION_REQUEST', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'Enable Old AUTOPILOT_VERSION_REQUEST mesage', 0, None), # noqa
|
||||
Feature('MAVLink', 'REQUEST_AUTOPILOT_CAPA', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'Enable Old REQUEST_AUTOPILOT_CAPABILITIES command', 0, None), # noqa
|
||||
Feature('MAVLink', 'MAV_MSG_RELAY_STATUS', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'Enable Send RELAY_STATUS message', 0, 'RELAY'), # noqa
|
||||
Feature('MAVLink', 'MAV_MSG_HIL_GPS', 'AP_MAVLINK_MSG_HIL_GPS_ENABLED', 'Enable Receive HIL_GPS messages', 0, 'MAV'), # noqa
|
||||
Feature('MAVLink', 'MAV_MSG_MOUNT_CONTROL', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'Enable Deprecated MOUNT_CONTROL message', 0, "MOUNT"), # noqa
|
||||
Feature('MAVLink', 'MAV_MSG_MOUNT_CONFIGURE', 'AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', 'Enable Deprecated MOUNT_CONFIGURE message', 0, "MOUNT"), # noqa
|
||||
Feature('MAVLink', 'AP_MAVLINK_BATTERY2_ENABLED', 'AP_MAVLINK_BATTERY2_ENABLED', 'Enable Send old BATTERY2 message', 0, None), # noqa
|
||||
|
@ -273,7 +273,6 @@ class ExtractFeatures(object):
|
||||
('AP_CUSTOMROTATIONS_ENABLED', 'AP_CustomRotations::init'),
|
||||
('AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', r'AP_OSD_Screen::draw_rc_tx_power'),
|
||||
('HAL_ENABLE_DRONECAN_DRIVERS', r'AP_DroneCAN::init'),
|
||||
('AP_MAVLINK_MSG_HIL_GPS_ENABLED', r'mavlink_msg_hil_gps_decode'),
|
||||
('AP_BARO_PROBE_EXTERNAL_I2C_BUSES', r'AP_Baro::_probe_i2c_barometers'),
|
||||
('AP_RSSI_ENABLED', r'AP_RSSI::init'),
|
||||
|
||||
|
@ -60,7 +60,7 @@ class AStyleChecker(object):
|
||||
self.progress("astyle check failed: (%s)" % (ret.stdout))
|
||||
self.retcode = 1
|
||||
if "Formatted" in ret.stdout:
|
||||
self.progress("Files needing formatting found")
|
||||
self.progress("Files needing formatting found.")
|
||||
print(ret.stdout)
|
||||
self.retcode = 1
|
||||
|
||||
|
@ -17,7 +17,6 @@ module load graph
|
||||
@alias add odroidpower relay set 0
|
||||
@alias add neutral2 servo set 12 1500
|
||||
@alias add ekf param set AHRS_EKF_USE
|
||||
@alias add gpsdisable param set SIM_GPS_DISABLE
|
||||
@alias add bb status gps* scaled* raw*
|
||||
@alias add g graph
|
||||
@alias add grc3 g RC_CHANNELS.chan3_raw SERVO_OUTPUT_RAW.servo3_raw
|
||||
|
@ -17,5 +17,5 @@
|
||||
// ArduPilot 4.7 stops compiling them in
|
||||
// ArduPilot 4.8 removes the code entirely
|
||||
#ifndef AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
|
||||
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT HAL_GCS_ENABLED && AP_FENCE_ENABLED
|
||||
#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 0
|
||||
#endif
|
||||
|
@ -618,9 +618,9 @@ public:
|
||||
// return current vibration vector for primary IMU
|
||||
Vector3f get_vibration(void) const;
|
||||
|
||||
// return primary accels, for lua
|
||||
// return primary accels
|
||||
const Vector3f &get_accel(void) const {
|
||||
return AP::ins().get_accel();
|
||||
return AP::ins().get_accel(_get_primary_accel_index());
|
||||
}
|
||||
|
||||
// return primary accel bias. This should be subtracted from
|
||||
|
@ -157,7 +157,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
|
||||
|
||||
// @Param: _OFF_PCNT
|
||||
// @DisplayName: Maximum offset cal speed error
|
||||
// @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered.
|
||||
// @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered.
|
||||
// @Range: 0.0 10.0
|
||||
// @Units: %
|
||||
// @User: Advanced
|
||||
|
@ -13,21 +13,15 @@ extern const AP_HAL::HAL& hal;
|
||||
AP_Airspeed_DroneCAN::DetectedModules AP_Airspeed_DroneCAN::_detected_modules[];
|
||||
HAL_Semaphore AP_Airspeed_DroneCAN::_sem_registry;
|
||||
|
||||
void AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
bool AP_Airspeed_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("airspeed_sub");
|
||||
}
|
||||
const auto driver_index = ap_dronecan->get_driver_index();
|
||||
|
||||
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_airspeed, driver_index) != nullptr)
|
||||
#if AP_AIRSPEED_HYGROMETER_ENABLE
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("hygrometer_sub");
|
||||
}
|
||||
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_hygrometer, driver_index) != nullptr)
|
||||
#endif
|
||||
;
|
||||
}
|
||||
|
||||
AP_Airspeed_Backend* AP_Airspeed_DroneCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid)
|
||||
|
@ -26,7 +26,7 @@ public:
|
||||
bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override;
|
||||
#endif
|
||||
|
||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
|
||||
static AP_Airspeed_Backend* probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid);
|
||||
|
||||
|
@ -582,11 +582,11 @@ bool AP_Arming::compass_checks(bool report)
|
||||
(double)MAX(fabsf(diff_mgauss.x), (double)fabsf(diff_mgauss.y)), (int)magfield_error_threshold);
|
||||
return false;
|
||||
}
|
||||
if (fabsf(diff_mgauss.x) > magfield_error_threshold*2.0) {
|
||||
if (fabsf(diff_mgauss.z) > magfield_error_threshold*2.0) {
|
||||
check_failed(ARMING_CHECK_COMPASS, report, "Check mag field (z diff:%.0f>%d)",
|
||||
(double)fabsf(diff_mgauss.z), (int)magfield_error_threshold*2);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // AP_AHRS_ENABLED
|
||||
}
|
||||
|
@ -21,18 +21,13 @@ AP_Baro_DroneCAN::AP_Baro_DroneCAN(AP_Baro &baro) :
|
||||
AP_Baro_Backend(baro)
|
||||
{}
|
||||
|
||||
void AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
bool AP_Baro_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
}
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("pressure_sub");
|
||||
}
|
||||
const auto driver_index = ap_dronecan->get_driver_index();
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("temperature_sub");
|
||||
}
|
||||
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_pressure, driver_index) != nullptr)
|
||||
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_temperature, driver_index) != nullptr)
|
||||
;
|
||||
}
|
||||
|
||||
AP_Baro_Backend* AP_Baro_DroneCAN::probe(AP_Baro &baro)
|
||||
|
@ -15,7 +15,7 @@ public:
|
||||
|
||||
void update() override;
|
||||
|
||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static AP_Baro_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, bool create_new);
|
||||
static AP_Baro_Backend* probe(AP_Baro &baro);
|
||||
|
||||
|
@ -42,23 +42,14 @@ AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMon
|
||||
_state.healthy = false;
|
||||
}
|
||||
|
||||
void AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
bool AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
|
||||
{
|
||||
if (ap_dronecan == nullptr) {
|
||||
return;
|
||||
}
|
||||
const auto driver_index = ap_dronecan->get_driver_index();
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("battinfo_sub");
|
||||
}
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("battinfo_aux_sub");
|
||||
}
|
||||
|
||||
if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, ap_dronecan->get_driver_index()) == nullptr) {
|
||||
AP_BoardConfig::allocation_error("mppt_stream_sub");
|
||||
}
|
||||
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_trampoline, driver_index) != nullptr)
|
||||
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_battery_info_aux_trampoline, driver_index) != nullptr)
|
||||
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_mppt_stream_trampoline, driver_index) != nullptr)
|
||||
;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -47,7 +47,7 @@ public:
|
||||
// return mavlink fault bitmask (see MAV_BATTERY_FAULT enum)
|
||||
uint32_t get_mavlink_fault_bitmask() const override;
|
||||
|
||||
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static bool subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
||||
static AP_BattMonitor_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id);
|
||||
static void handle_battery_info_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_power_BatteryInfo &msg);
|
||||
static void handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg);
|
||||
|
@ -150,14 +150,16 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
|
||||
AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),
|
||||
|
||||
// 20 was BUS
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if AP_BATTERY_OPTIONS_PARAM_ENABLED
|
||||
// @Param: OPTIONS
|
||||
// @DisplayName: Battery monitor options
|
||||
// @Description: This sets options to change the behaviour of the battery monitor
|
||||
// @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS, 7:Allow DroneCAN InfoAux to be from a different CAN node, 9:Sum monitor measures minimum voltage instead of average
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0),
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
#endif // AP_BATTERY_OPTIONS_PARAM_ENABLED
|
||||
|
||||
#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
|
||||
// @Param: ESC_INDEX
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user