Attendees (max): 11
ArduPilot:master
← robertlong13:pr/sum_monitor_min_voltage
opened 03:10AM - 25 Sep 24 UTC
Alternative approach to #28148
This solves the race condition issue and the W… h consumption calculation. Instead of calling `update_consumed` again, it sums the consumption calculation from the other monitors. This is actually much better than integrating it again manually, especially if the underlying monitors are better at calculating the consumption.
I also removed the implementation on the ESC battmon backend (and updated the param docs and comments to match). I don't think it was nearly as important to have this option for the ESC backend and I couldn't use the same trick with that one.
UTC0701
Peter : Approved
We need Tridge to merge this.
ArduPilot:master
← peterbarker:pr/fix-mft-100
opened 02:28AM - 25 Sep 24 UTC
this board uses 2 128kB sectors for storage, meaning it is very short on space
…
Remove features we are likely to remove for everyone in 4.7
![image](https://github.com/user-attachments/assets/a958aac7-9843-4bd9-8762-507b49485e3b)
@EternAlmox - those 128kB sectors really do hurt the available flash on these boards.
We're looking at putting a feature in to use a single page of storage for parameters, but that's problematic from both a migration POV and from a data sanctity POV (there's a race condition when "compacting" storage when it fills up). We'll see how we go.
UTC0708
Andy : We could use -Os to shrink the binary.
P : Let’s try that.
ArduPilot:master
← peterbarker:pr/fix-jhemcu
opened 12:46AM - 25 Sep 24 UTC
This board is overflowing available flash (https://firmware.ardupilot.org/Tools/… BuildSizes/builds.html)
Minimise it.
Change in features included:
```
pbarker@fx:/tmp/tmpn9o0wioe$ diff -u /tmp/b /tmp/a
--- /tmp/b 2024-09-25 10:40:31.433073265 +1000
+++ /tmp/a 2024-09-25 10:40:24.161104331 +1000
@@ -1,4 +1,4 @@
-AC_PAYLOAD_PLACE_ENABLED
+!AC_PAYLOAD_PLACE_ENABLED
AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT
!AC_PRECLAND_COMPANION_ENABLED
!AC_PRECLAND_ENABLED
@@ -11,50 +11,50 @@
!AP_ADVANCEDFAILSAFE_ENABLED
AP_AIRSPEED_ANALOG_ENABLED
AP_AIRSPEED_ASP5033_ENABLED
-AP_AIRSPEED_DLVR_ENABLED
+!AP_AIRSPEED_DLVR_ENABLED
!AP_AIRSPEED_DRONECAN_ENABLED
AP_AIRSPEED_ENABLED
AP_AIRSPEED_MS4525_ENABLED
AP_AIRSPEED_MS5525_ENABLED
-AP_AIRSPEED_MSP_ENABLED
+!AP_AIRSPEED_MSP_ENABLED
!AP_AIRSPEED_NMEA_ENABLED
AP_AIRSPEED_SDP3X_ENABLED
AP_AIS_ENABLED
AP_AVOIDANCE_ENABLED
-AP_BARO_BMP085_ENABLED
+!AP_BARO_BMP085_ENABLED
AP_BARO_BMP280_ENABLED
-AP_BARO_BMP388_ENABLED
-AP_BARO_BMP581_ENABLED
-AP_BARO_DPS280_ENABLED
+!AP_BARO_BMP388_ENABLED
+!AP_BARO_BMP581_ENABLED
+!AP_BARO_DPS280_ENABLED
!AP_BARO_DRONECAN_ENABLED
AP_BARO_EXTERNALAHRS_ENABLED
-AP_BARO_FBM320_ENABLED
+!AP_BARO_FBM320_ENABLED
!AP_BARO_KELLERLD_ENABLED
-AP_BARO_LPS2XH_ENABLED
+!AP_BARO_LPS2XH_ENABLED
AP_BARO_MS56XX_ENABLED
AP_BARO_MSP_ENABLED
-AP_BARO_PROBE_EXTERNAL_I2C_BUSES
-AP_BARO_SPL06_ENABLED
+!AP_BARO_PROBE_EXTERNAL_I2C_BUSES
+!AP_BARO_SPL06_ENABLED
!HAL_BARO_WIND_COMP_ENABLED
!AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED
-AP_BATTERY_FUELFLOW_ENABLED
-AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
-AP_BATTERY_FUELLEVEL_PWM_ENABLED
-AP_BATTERY_INA2XX_ENABLED
+!AP_BATTERY_FUELFLOW_ENABLED
+!AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
+!AP_BATTERY_FUELLEVEL_PWM_ENABLED
+!AP_BATTERY_INA2XX_ENABLED
!AP_BATTERY_SMBUS_ENABLED
AP_BATTERY_SUM_ENABLED
AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
!AP_BATTERY_WATT_MAX_ENABLED
-AP_BEACON_ENABLED
+!AP_BEACON_ENABLED
AP_BOOTLOADER_FLASHING_ENABLED
-!HAL_BUTTON_ENABLED
+HAL_BUTTON_ENABLED
AP_CAMERA_ENABLED
-AP_CAMERA_MAVLINKCAMV2_ENABLED
-AP_CAMERA_MAVLINK_ENABLED
-AP_CAMERA_MOUNT_ENABLED
+!AP_CAMERA_MAVLINKCAMV2_ENABLED
+!AP_CAMERA_MAVLINK_ENABLED
+!AP_CAMERA_MOUNT_ENABLED
AP_CAMERA_RELAY_ENABLED
!AP_CAMERA_SEND_FOV_STATUS_ENABLED
-AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
+!AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
AP_CAMERA_SERVO_ENABLED
!AP_CAMERA_SOLOGIMBAL_ENABLED
!AP_CAN_SLCAN_ENABLED
@@ -83,7 +83,7 @@
HAL_CRSF_TELEM_ENABLED
HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED
AP_CUSTOMROTATIONS_ENABLED
-HAL_DISPLAY_ENABLED
+!HAL_DISPLAY_ENABLED
!AP_DRONECAN_HIMARK_SERVO_SUPPORT
!AP_DRONECAN_HOBBYWING_ESC_SUPPORT
!AP_DRONECAN_SEND_GPS
@@ -120,27 +120,27 @@
!AP_GENERATOR_IE_650_800_ENABLED
!AP_GENERATOR_RICHENPOWER_ENABLED
AP_GHST_TELEM_ENABLED
-AP_GPS_BLENDED_ENABLED
-AP_GPS_ERB_ENABLED
-AP_GPS_GSOF_ENABLED
-AP_GPS_MAV_ENABLED
+!AP_GPS_BLENDED_ENABLED
+!AP_GPS_ERB_ENABLED
+!AP_GPS_GSOF_ENABLED
+!AP_GPS_MAV_ENABLED
AP_GPS_NMEA_ENABLED
AP_GPS_NMEA_UNICORE_ENABLED
-AP_GPS_NOVA_ENABLED
-AP_GPS_SBF_ENABLED
-AP_GPS_SBP2_ENABLED
-AP_GPS_SBP_ENABLED
-AP_GPS_SIRF_ENABLED
+!AP_GPS_NOVA_ENABLED
+!AP_GPS_SBF_ENABLED
+!AP_GPS_SBP2_ENABLED
+!AP_GPS_SBP_ENABLED
+!AP_GPS_SIRF_ENABLED
AP_GPS_UBLOX_ENABLED
!AP_GRIPPER_ENABLED
!HAL_GYROFFT_ENABLED
-HAL_HIGH_LATENCY2_ENABLED
+!HAL_HIGH_LATENCY2_ENABLED
!HAL_HOTT_TELEM_ENABLED
!AP_IBUS_TELEM_ENABLED
!AP_ICENGINE_ENABLED
AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
-AP_INERTIALSENSOR_KILL_IMU_ENABLED
+!AP_INERTIALSENSOR_KILL_IMU_ENABLED
HAL_INS_TEMPERATURE_CAL_ENABLE
!AP_KDECAN_ENABLED
AP_LANDINGGEAR_ENABLED
@@ -158,31 +158,31 @@
!AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED
!AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED
AP_MAVLINK_MSG_RC_CHANNELS_RAW_ENABLED
-AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
+!AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED
AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED
AP_MAVLINK_SERVO_RELAY_ENABLED
-AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
-AP_MOTORS_FRAME_DECA_ENABLED
-AP_MOTORS_FRAME_DODECAHEXA_ENABLED
+!AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
+!AP_MOTORS_FRAME_DECA_ENABLED
+!AP_MOTORS_FRAME_DODECAHEXA_ENABLED
AP_MOTORS_FRAME_HEXA_ENABLED
-AP_MOTORS_FRAME_OCTAQUAD_ENABLED
+!AP_MOTORS_FRAME_OCTAQUAD_ENABLED
AP_MOTORS_FRAME_OCTA_ENABLED
AP_MOTORS_FRAME_QUAD_ENABLED
-AP_MOTORS_FRAME_Y6_ENABLED
-HAL_MOUNT_ALEXMOS_ENABLED
-HAL_MOUNT_ENABLED
-HAL_MOUNT_GREMSY_ENABLED
-HAL_MOUNT_SERVO_ENABLED
-HAL_MOUNT_SIYI_ENABLED
-HAL_MOUNT_STORM32MAVLINK_ENABLED
-HAL_MOUNT_STORM32SERIAL_ENABLED
-HAL_MOUNT_TOPOTEK_ENABLED
-HAL_MOUNT_VIEWPRO_ENABLED
+!AP_MOTORS_FRAME_Y6_ENABLED
+!HAL_MOUNT_ALEXMOS_ENABLED
+!HAL_MOUNT_ENABLED
+!HAL_MOUNT_GREMSY_ENABLED
+!HAL_MOUNT_SERVO_ENABLED
+!HAL_MOUNT_SIYI_ENABLED
+!HAL_MOUNT_STORM32MAVLINK_ENABLED
+!HAL_MOUNT_STORM32SERIAL_ENABLED
+!HAL_MOUNT_TOPOTEK_ENABLED
+!HAL_MOUNT_VIEWPRO_ENABLED
!HAL_MOUNT_XACTI_ENABLED
HAL_MSP_ENABLED
HAL_MSP_GPS_ENABLED
-HAL_MSP_OPTICALFLOW_ENABLED
+!HAL_MSP_OPTICALFLOW_ENABLED
HAL_MSP_RANGEFINDER_ENABLED
!HAL_MSP_SENSORS_ENABLED
!HAL_NAVEKF2_AVAILABLE
@@ -192,21 +192,21 @@
!HAL_NMEA_OUTPUT_ENABLED
AP_NOTIFY_MAVLINK_LED_CONTROL_SUPPORT_ENABLED
AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
-AP_NOTIFY_NCP5623_ENABLED
+!AP_NOTIFY_NCP5623_ENABLED
AP_NOTIFY_NEOPIXEL_ENABLED
AP_NOTIFY_PROFILED_ENABLED
!AP_NOTIFY_PROFILED_SPI_ENABLED
AP_NOTIFY_TONEALARM_ENABLED
!AP_OAPATHPLANNER_ENABLED
!AP_OPENDRONEID_ENABLED
-AP_OPTICALFLOW_CXOF_ENABLED
-AP_OPTICALFLOW_ENABLED
+!AP_OPTICALFLOW_CXOF_ENABLED
+!AP_OPTICALFLOW_ENABLED
!AP_OPTICALFLOW_HEREFLOW_ENABLED
-AP_OPTICALFLOW_MAV_ENABLED
+!AP_OPTICALFLOW_MAV_ENABLED
!AP_OPTICALFLOW_ONBOARD_ENABLED
-AP_OPTICALFLOW_PIXART_ENABLED
-AP_OPTICALFLOW_PX4FLOW_ENABLED
-AP_OPTICALFLOW_UPFLOW_ENABLED
+!AP_OPTICALFLOW_PIXART_ENABLED
+!AP_OPTICALFLOW_PX4FLOW_ENABLED
+!AP_OPTICALFLOW_UPFLOW_ENABLED
!AP_OSD_LINK_STATS_EXTENSIONS_ENABLED
HAL_OSD_SIDEBAR_ENABLE
!HAL_PARACHUTE_ENABLED
@@ -275,7 +275,7 @@
AP_RCPROTOCOL_SRXL_ENABLED
AP_RCPROTOCOL_ST24_ENABLED
AP_RCPROTOCOL_SUMD_ENABLED
-AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
+!AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED
AP_RELAY_ENABLED
AP_ROBOTISSERVO_ENABLED
!AP_ROVER_ADVANCED_FAILSAFE_ENABLED
@@ -288,7 +288,7 @@
AP_RPM_PIN_ENABLED
AP_RSSI_ENABLED
HAL_RUNCAM_ENABLED
-AP_SBUSOUTPUT_ENABLED
+!AP_SBUSOUTPUT_ENABLED
AP_SCRIPTING_ENABLED
!AP_SCRIPTING_SERIALDEVICE_ENABLED
!AP_SDCARD_STORAGE_ENABLED
@@ -312,27 +312,27 @@
AP_VIDEOTX_ENABLED
HAL_VISUALODOM_ENABLED
AP_VOLZ_ENABLED
-AP_WINCH_DAIWA_ENABLED
-AP_WINCH_ENABLED
-AP_WINCH_PWM_ENABLED
+!AP_WINCH_DAIWA_ENABLED
+!AP_WINCH_ENABLED
+!AP_WINCH_PWM_ENABLED
HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
HAL_WITH_MSP_DISPLAYPORT
COMPASS_CAL_ENABLED
COMPASS_LEARN_ENABLED
EK3_FEATURE_DRAG_FUSION
EK3_FEATURE_EXTERNAL_NAV
-EK3_FEATURE_OPTFLOW_FUSION
+!EK3_FEATURE_OPTFLOW_FUSION
!FORCE_APJ_DEFAULT_PARAMETERS
-GPS_MOVING_BASELINE
+!GPS_MOVING_BASELINE
MODE_BRAKE_ENABLED
MODE_FLIP_ENABLED
-MODE_FLOWHOLD_ENABLED
-MODE_FOLLOW_ENABLED
-MODE_GUIDED_NOGPS_ENABLED
+!MODE_FLOWHOLD_ENABLED
+!MODE_FOLLOW_ENABLED
+!MODE_GUIDED_NOGPS_ENABLED
!MODE_SPORT_ENABLED
-MODE_SYSTEMID_ENABLED
+!MODE_SYSTEMID_ENABLED
MODE_TURTLE_ENABLED
-MODE_ZIGZAG_ENABLED
+!MODE_ZIGZAG_ENABLED
OSD_ENABLED
OSD_PARAM_ENABLED
!QAUTOTUNE_ENABLED
```
... for Copter-only minimized boards we should probably add `define AP_AIRSPEED_ENABLED 0` to their hwdefs.
@ot0tot for visibility
UTC0711
Andy : Approved
ArduPilot:master
← andyp1per:pr-gain-backoff-test
opened 11:38AM - 24 Sep 24 UTC
UTC0713
George : Not relevant to the test, but this feature will cause reduction in gains, if there is a false-positive land detection mid-flight. We’ve had one or two of these.
Andy,P: That’s correct.
ArduPilot:master
← peterbarker:pr/CubeBlack-EKF2
opened 06:04AM - 17 Sep 24 UTC
we really just care that EKF2 builds here, the board really isn't that important
UTC0721
Andrew : This was caused by an alignment of 2-3 different bugs and it made the CANARD bug surface.
P : We could ask a user of dronecan ESCs to test.
Bob : I can do it.
A : We also need Michel to release Mission Planner in tandem.
P : Why 100us delay?
A : It’s just enough to work, without lowering the bandwidth significantly.
For H7 boards unfortunately we can fit only up to 128 CAN messages. This makes the bug more pronounced.
P : Testing on HW would be very sensible.
ArduPilot:master
← peterbarker:pr/bitmask-split-out-in-xml
opened 09:43AM - 24 Sep 24 UTC
make it easy for consumers to get at this data.
leaves the old form, so we do… n't break older consumers
```
pbarker@fx:~/rc/ardupilot(master)$ ls -l apm.pdef.xml apm.pdef.xml-new
-rw-rw-r-- 1 pbarker pbarker 2137562 Sep 24 19:41 apm.pdef.xml
-rw-rw-r-- 1 pbarker pbarker 2248139 Sep 24 19:40 apm.pdef.xml-new
pbarker@fx:~/rc/ardupilot(master)$ ls -l apm.pdef.xml apm.pdef.xml-new --si
-rw-rw-r-- 1 pbarker pbarker 2.2M Sep 24 19:41 apm.pdef.xml
-rw-rw-r-- 1 pbarker pbarker 2.3M Sep 24 19:40 apm.pdef.xml-new
pbarker@fx:~/rc/ardupilot(master)$
```
There are only lines added to the XML.
```
--- apm.pdef.xml 2024-09-24 19:41:10.625061443 +1000
+++ apm.pdef.xml-new 2024-09-24 19:40:53.980125704 +1000
@@ -17,6 +17,10 @@
<field name="Increment">1</field>
</param>
<param humanName="Autotune options bitmask" name="ArduPlane:AUTOTUNE_OPTIONS" documentation="Fixed Wing Autotune specific options. Useful on QuadPlanes with higher INS_GYRO_FILTER settings to prevent these filter values from being set too agressively during Fixed Wing Autotune." user="Advanced">
+ <bitmask>
+ <bit code="0"> Disable FLTD update by Autotune</bit>
+ <bit code="1"> Disable FLTT update by Autotune</bit>
+ </bitmask>
<field name="Bitmask">0: Disable FLTD update by Autotune, 1: Disable FLTT update by Autotune</field>
</param>
<param humanName="Telemetry startup delay" name="ArduPlane:TELEM_DELAY" documentation="The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up" user="Standard">
```
UTC0733
A : Future feature: We could add a param setbit, getbit in MAVProxy.
P : MergeOnCIPass
ArduPilot:master
← peterbarker:pr/global-nan
opened 04:29AM - 24 Sep 24 UTC
per-spec
Replaces https://github.com/ArduPilot/ardupilot/pull/25010/files
… Creates a global `NaNf` per @rmackay9 's suggestion
UTC0738
A : Looks good
P : We need Randy to approve.
ArduPilot:master
← muramura:AP_Set_the_message_buffer_size_to_twice_the_message_size
opened 02:46AM - 24 Sep 24 UTC
The number of characters in the message exceeds 50 bytes.
The message array is… currently set to 50 bytes. I will submit a PR to change the array to 100 bytes.
ArduPilot has string splitting functionality.
AFTER
![Screenshot from 2024-09-24 11-26-39](https://github.com/user-attachments/assets/97517eab-9fef-49ba-a0e5-dc926e612d8f)
BEFORE
![Screenshot from 2024-09-24 09-58-46](https://github.com/user-attachments/assets/b389a65c-3808-4c37-a61f-cb25a049644e)
THIS SOURCE:
![Screenshot from 2024-09-24 09-59-20](https://github.com/user-attachments/assets/6de775f6-f0a0-4fa4-980b-5703397a9214)
UTC0743
A : Seems reasonable.
P : We need Randy to approve.
ArduPilot:master
← robertlong13:pr/ice-starter-safety
opened 07:12AM - 23 Sep 24 UTC
If you set the option bit for "allow throttle while disarmed", you can crank the… starter even while the safety switch is engaged, and unless you use a servo pwm as your starter motor controller, you can't even configure it to not do that.
Some places use the `allow_throttle_while_disarmed` method, which additionally checks the safety switch. Other places directly check the options bit. So some stuff works with the safety engaged, and other parts don't. This PR just unifies everything to use the same check.
UTC0744
B : Other places were using allow_throttle_while_disarmed()
. Brought it here as well.
A : There is a case of users having safety enabled but exclude the starter motor. This change would mean that they will get running throttle.
P : We should merge this and if someone complains, we add an OPTION bit.
A : MergeOnCIPass
ArduPilot:master
← srmainwaring:prs/pr-gst-examples
opened 09:16AM - 21 Sep 24 UTC
Python examples demonstrating how to manipulate UDP and RTSP video streams using… GStreamer.
The UDP to RTSP converter addresses the problem of consuming a simulated video stream from Gazebo in more than one application using standard installations of GStreamer and opencv (no need for a custom build and install of opencv).
### Related:
- https://github.com/ArduPilot/ardupilot/pull/27773
- https://github.com/ArduPilot/ardupilot/pull/27903
- https://github.com/ArduPilot/ardupilot_gazebo?tab=readme-ov-file#3-streaming-camera-video
UTC0752
P : Rhys will agree with Randy on where to place the new scripts.
ArduPilot:master
← andyp1per:pr-att-dt
opened 08:51PM - 14 Aug 24 UTC
Broken out from https://github.com/ArduPilot/ardupilot/pull/27029
The essence… of these changes is to make sure that the interaction between the attitude controller and the rate controller are thread safe. This involves avoiding setting object state as intermediate values but instead publishing at the end of a calculation. It also means that changes should be accepted as vectors rather than discrete axes. Experiments were also done using locking but this proved to be moderately expensive at high update rates and did not improve the overall effect of this change.
UTC0803
A : I’m happy to approve it.
Andy : We’ll wait for Bill to approve, then merge.
ArduPilot:master
← peterbarker:pr/reorder-initialisers
opened 06:09AM - 20 Sep 24 UTC
we were bitten by a nasty bug in CAN because of constructor reordering
Rearra… nges the constructor lists for Plane and Copter.
These do change the output binary sizes.
UTC0808
P : Still failing tests.
Revo Mini grew by 500B.
Some work needed to be done still
ArduPilot:master
← peterbarker:pr/periph-must-define-gps-to-1-or-0
opened 05:49AM - 17 Sep 24 UTC
UTC0814
P : Needs testing.
ArduPilot:master
← bugobliterator:pr-spi-perf
opened 06:48AM - 13 Sep 24 UTC
* Tested on CubeOrangePlus and CubeRedPrimary with Invensensev3 driver
* I us… ed debug trace to analyse timeline for read_fifo to check if we have any substantial overhead while doing SPI transactions. It turned out that calling spiStart and spiStop which in turn call dmaStreamAlloc and and dealloc to take substantial amount of CPU call almost 3-4us. Also we were calling Shared DMA mutex lock and unlock when the DMA is not shared between peripherals.
* Following changes made SPI transactions much less CPU intensive:
- * Do not reset SPI peripheral using spistop and spistart calls if SPI config hasn't changed.
- * Also make changes to SPI frequencies for CubeOrangePlus and CubeRedPrimary to match on the bus where possible (minor CPU gain through this, just first part was enough as most transactions are IMU anyways).
- * Do not call mutex lock unlock for unshared DMAs.
Results:
CubeRedPrimary:
Before:
SPI1 PRI=181 sp=0x20001AA8 STACK= 792/1464 LOAD=13.4%
SPI4 PRI=181 sp=0x200021C0 STACK= 872/1464 LOAD=13.4%
SPI2 PRI=181 sp=0x20005380 STACK= 896/1464 LOAD=13.3%
After:
SPI1 PRI=181 sp=0x20001B08 STACK= 792/1464 LOAD= 9.7%
SPI4 PRI=181 sp=0x20002220 STACK= 792/1464 LOAD=11.2%
SPI2 PRI=181 sp=0x200053E0 STACK= 840/1464 LOAD= 8.3%
CubeOrangePlus:
Before:
SPI4 PRI=181 sp=0x3002AF58 STACK= 668/1464 LOAD=25.5%
SPI1 PRI=181 sp=0x3002B668 STACK= 668/1464 LOAD=14.5%
After:
SPI4 PRI=181 sp=0x3002AF78 STACK= 668/1464 LOAD=19.2%
SPI1 PRI=181 sp=0x3002B688 STACK= 668/1464 LOAD= 9.5%
>10% total CPU time recovered for both CubeOrangePlus and CubeRedPrimary
UTC0815
A : I need to talk to Sid about this when he’s available again.
The Invensense driver now does a lot more SPI transactions and this has increased the CPU load a lot.
Hopefully Sid and Andy will agree to something in the next few days.
ArduPilot:master
← loki077:Max-engine-cranking-retrial
opened 02:52AM - 26 Aug 24 UTC
As we use a common battery for Avionics and Engine Cranking we would like to hav… e an option to limit the number of retrials so that it doesn't drain that battery completely. Obvious choice is to separate the batteries but I still think there could be some use of this feature.
My Implementation is by adding Param MAX_RETRY which If set 0 then there is no limit to retrials. If set to a value greater than 0 then the engine will retry starting the engine this many times before giving up. Also the counter to track retrials resets to zero on disarm (could be done only on power cycle rather than disarm). If needed to be override can be done by setting the param to 0.
I would like to get more ideas on the method of its implementation. I have not yest tested this code.
Other ways to implement this is by just keep increasing the time between retrials.
UTC0820
P : There might be a context-related bug in the autotest.
B : I’ll take another look.
ArduPilot:master
← Winjeel:upstream/lua-camera-information
opened 08:12AM - 08 Aug 24 UTC
This PR allows us to populate the [`CAMERA_INFORMATION`](https://mavlink.io/en/m… essages/common.html#CAMERA_INFORMATION) and [`VIDEO_STREAM_INFORMATION`](https://mavlink.io/en/messages/common.html#VIDEO_STREAM_INFORMATION) MAVLink messages from Lua scripts.
Sending these messages allows a GCS to auto-configure the video stream to receive video from the payload.
Replaces https://github.com/ArduPilot/ardupilot/pull/27594.
UTC0829
P : A bit unusre what the _rsem
is for.
A : Probably to prevent scripting calls corrupt data.
P : Do we want the automatic scripting backend enable?
Do we need to explicitly create a new binding for the video stream information? Can’t the new MAVLink lua module provide something similar? This costs quite a bit of flash.
Also needs Randy’s approval.
ArduPilot:master
← Georacer:pr/tecs_improvements
opened 03:45PM - 05 Aug 24 UTC
This PR fixes TECS oscillations that would occur once mode TAKEOFF would reach `… TKOFF_ALT`.
Additionally, it harmonizes the takeoff behaviour between modes AUTO and TAKEOFF.
Finally, it fixes a few bugs.
Many thanks to @Hwurzburg for sharing code for fixing the pitch setpoint.
## Notable behaviour changes
1. Mode TAKEOFF and AUTO now behave identically during a takeoff.
2. `TKOFF_LVL_ALT` now also affects AUTO mode.
3. TAKEOFF mode now respects the level-off angles, as it approaches altitude. There should now be significantly less overshoot.
4. The behaviour of TKOFF_ROTATION_SPD now works as advertized. It was inactive before.
## Notable code changes
1. Mode TAKEOFF now spends all of the climb in FlightStage::TAKEOFF, just like AUTO mode did.
2. `TECS::set_pitch_max_limit()` is now split into `TECS::set_pitch_max()` and `TECS::set_pitch_min()`. Its usage in `quadplane.cpp` has been modified accordingly.
3. TECS pitch limits are now applied at the end of the calculation. Before, vertical acceleration limitations were applied last.
5. TECS: `_post_TO_hgt_offset` will now never pull height demand above the target altitude.
6. `mode_takeoff.cpp` is now prevented from switching behaviours from past `TKOFF_ALT`-2m back to climb behaviour. This would cause behaviour switching if the plane would drop slightly lower than 2m from `TKOFF_ALT`.
7. There are many occasions were TECS is overridden both in pitch and throttle. When that happens, TECS is now effectively inactive and will reset itself.
8. Changed behaviour of `TECS_PITCH_MIN` to match description.
9. `servos.cpp` now doesn't try to enforce all of the takeoff throttle logic combinations. Only `TKOFF_THR_MAX` and `TKOFF_THR_MIN`.
## Tests
The following were tested in autotests:
1. Altitude and pitch no longer oscillation upon reaching the takeoff altitude. ✅
2. TAKEOFF and AUTO takeoffs now behave exactly the same in all combinations of `ARSPD_USE` and `TKOFF_OPTIONS`. ✅
3. The level-off of minimum pitch demand now works in TAKEOFF. ✅
4. When `TKOFF_ROTATE_SPD` is nonzero, pitch demand will be 5deg before the rotation speed and will climb up to the minimum takeoff pitch for groundspeed equal to cruise airspeed. ✅
The following were tested in manual SITL:
1. Altitude and pitch no longer oscillation upon reaching the takeoff altitude. ✅
2. The level-off of minimum pitch demand now works in TAKEOFF. ✅
3. When `TKOFF_ROTATE_SPD` is nonzero, pitch demand will be 5deg before the rotation speed and will climb up to the minimum takeoff pitch for groundspeed equal to cruise airspeed. ✅
## Known issues
1. Ground speed is used in some airspeed comparisons.
5. If AUTO is engaged while in flight and has a NAV_TAKEOFF point, it will force the pitch to positive while it gets processed. This lasts for a few cycles.
6. The SITL plane doesn't regulate pitch well when it's flying at full throttle and fast. Nothing to do with this PR, just an observation.
## Future work
1. I noticed that if you load a mission before you get a GNSS fix, the NAV_TAKEOFF waypoint (i.e. next_WP_loc) will be set at coordinates at the home coordinates and altitude. This can break some takeoff logic in AUTO mode.
2. Render `TKOFF_LVL_ALT` a higher-level parameter, as it is now used also by AUTO mode, not just TAKEOFF.
UTC0848
MergeOnCIPass
ArduPilot:master
← bugobliterator:pr-iomcu-profiled
opened 05:25AM - 02 Aug 24 UTC
* CPU time cost is minimal, only upto 7us per call is consumed.
* Flash and Dat… a Cost is as follows:
Before:
```
BUILD SUMMARY
Build directory: /home/sidbh/Programming/ardupilot-chibios/build/iomcu-f103-dshot
Target Text (B) Data (B) BSS (B) Total Flash Used (B) Free Flash (B) External Flash Used (B)
-------------------------------------------------------------------------------------------------------------------
bin/iofirmware_lowpolh 52404 1196 19300 53600 7836 Not Applicable
bin/iofirmware_highpolh 52404 1196 19300 53600 7836 Not Applicable
```
After
```
BUILD SUMMARY
Build directory: /home/sidbh/Programming/ardupilot-chibios/build/iomcu-f103-dshot
Target Text (B) Data (B) BSS (B) Total Flash Used (B) Free Flash (B) External Flash Used (B)
-------------------------------------------------------------------------------------------------------------------
bin/iofirmware_lowpolh 52160 1196 19296 53356 8084 Not Applicable
bin/iofirmware_highpolh 52160 1196 19296 53356 8084 Not Applicable
```
UTC0849
A : The Pixhawk6X ccache test is failing, even though the change shouldn’t affect it.
The Pixhawk6X binary grows by > 500B, which is very suspicious.
P : Perhaps -02 is leakiing to other places, potentially through the new header include?