Inconsistent Speed Change Behavior in ArduPilot's GUIDED Mode

Description
In GUIDED mode of ArduPilot, I encountered an issue where the commanded speed does not reflect the desired change. After sending the message MAV_CMD_NAV_WAYPOINT to specify a waypoint and then subsequently sending the message MAV_CMD_DO_CHANGE_SPEED to adjust the machine’s speed, the debugger indicates that the desired speed change is being set. However, the machine itself does not adjust its speed accordingly.

Version
Plane 4.3.2

Model

  • Zephyr delta wing

Platform

  • Plane

Hardware type

  • SITL

Upon further investigation, it has been observed that when sending the MAV_CMD_DO_CHANGE_SPEED message, the variable new_airspeed_cm in the code becomes 920. This value is obtained when using the following message parameters:

master.mav.command_long_encode( target_system, target_component, mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, 0, 0, # Speed type 9.2, # Desired speed in meters per second 0, 0, 0, 0, 0 )

Please let me know if there is any further information or clarification required.

Can you test ArduPlane 4.3.6?

Yes, I’m going to try it now.

Tried in version ArduPlane 4.3.6, the same situation, a screenshot attached:

The script that I run:

# Connect to autopilot via UDP
connection_string = 'udp:127.0.0.1:14550'
master = mavutil.mavlink_connection(connection_string, source_system=0)

# Wait for heartbeat and check connection status
master.wait_heartbeat()
print("Connection successful")

# Send the MAV_CMD_DO_CHANGE_SPEED command
msg = master.mav.command_long_encode(
    0, 0,
    mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
    0,  # Confirmation
    0,  # speed type
    9.2,
    0, 0, 0, 0, 0  # Param6, Param7 (Unused)
)

frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT

while(True):    
    wp = LocationGlobal(-35.3621576,149.176272, 800 - 20)    
    master.mav.mission_item_send(0, 0, 0, frame,
                                           mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2, 0, 0,
                                           0, 0, 0, wp.lat, wp.lon,
                                           800 - 20)
    time.sleep(0.1)
    master.mav.send(msg)

Even if you set the speed with the command, it is still limited between ARSPD_FBW_MIN and ARSPD_FBW_MAX. What are these settings?