PX4-Autopilot icon indicating copy to clipboard operation
PX4-Autopilot copied to clipboard

[pxh shell] param show results don't match the actual values of INT32 params set over MAVLink

Open squizz617 opened this issue 3 years ago • 6 comments
trafficstars

Describe the bug Hi. When I set the value of an INT32 parameter over MAVLink, and then request the param list (also over MAVLink), it shows the value I've set. However, on the pxh shell, weird values are shown when I do param show SOME_PARAM.

To Reproduce [Terminal 1] make px4_sitl_rtps gazebo -j4 [Terminal 2] download and run the PoC:

$ python3 poc/poc_px4_param.py
[*] (MAVLink) set param COM_OBL_RC_ACT := 5
name: COM_OBL_RC_ACT    value: 5
[*] (MAVLink) set param COM_OBL_ACT := 2
name: COM_OBL_ACT       value: 2

Back on [Terminal 1] check parameters

pxh> param show COM_OBL_RC_ACT                                        
Symbols: x = used, + = saved, * = unsaved
x + COM_OBL_RC_ACT [159,234] : 1084227584

 662/1429 parameters used.                                            
pxh> param show COM_OBL_ACT                                           
Symbols: x = used, + = saved, * = unsaved
x + COM_OBL_ACT [158,233] : 1073741824

 662/1429 parameters used. 

Expected behavior pxh shell should show the values properly, i.e., COM_OBL_RC_ACT: 5, COM_OBL_ACT: 2. Not sure whether this simply is an representation error on the shell, or those weird values are actually assigned to those parameters.

Log Files and Screenshots Flight review - Download > Parameters also shows the incorrect values:

COM_OBL_ACT, 1073741824
COM_OBL_RC_ACT, 1084227584

Drone (please complete the following information):

  • Build: px4_sitl_rtps
  • Commit: a2645418

Thank you!

squizz617 avatar Mar 02 '22 13:03 squizz617

Try it with a float, it's probably the encoding of the integer.

http://mavlink.io/en/messages/common.html#PARAM_SET

You need to put the actual byte representation of the integer into the value field, like if it were a union. https://github.com/PX4/PX4-Autopilot/blob/35af604a82927221fe4a9d4ad2379c0a8672e1e7/src/modules/mavlink/mavlink_parameters.cpp#L130-L131

dagar avatar Mar 02 '22 18:03 dagar

Thanks for the quick feedback @dagar.

Try it with a float, it's probably the encoding of the integer.

Both COM_BOL_RC_ACT and COM_OBL_ACT are INT32 parameters, and the attempts to set it as FLOAT are rejected by PX4. I've already fiddled with a few different parameters, and confirmed that the param change is only accepted when the type is set as INT32 (MAV_PARAM_TYPE_INT32 to be exact).

You need to put the actual byte representation of the integer into the value field

I believe the encoding is already handled by pymavlink's param_set_send API as shown in the PoC above, isn't it? For FLOAT parameters, param setting over MAVLink shows consistent values in both pxh shell and over MAVLink.

squizz617 avatar Mar 02 '22 18:03 squizz617

Both COM_BOL_RC_ACT and COM_OBL_ACT are INT32 parameters, and the attempts to set it as FLOAT are rejected by PX4.

I'm saying try setting an actual float parameter with a float value to validate if the rest is otherwise working.

I believe the encoding is already handled by pymavlink's param_set_send API as shown in the PoC above, isn't it? For FLOAT parameters, param setting over MAVLink shows consistent values in both pxh shell and over MAVLink.

I don't know, we'd have to dig into pymavlink source (it's a completely separate project). Some mavlink specific details here, but things evolved differently over the years due to ambiguity. http://mavlink.io/en/services/parameter.html#px4

dagar avatar Mar 02 '22 18:03 dagar

I'm saying try setting an actual float parameter with a float value

I see. I've confirmed that it works without any issue with the float parameters.

As you said, it seems like the issue could be on the pymavlink side. I'll talk to them. Thanks!

squizz617 avatar Mar 02 '22 18:03 squizz617

FYI @hamishwillee

dagar avatar Mar 02 '22 18:03 dagar

I still have the same issue. Some years later. Does anyone have any feedback on this? Setting parameters from pymavlink (int32) still doesn't work properly.

For the record, I found a workaround making the conversion manually before calling the pymavlink interface. For example (unsing import struct), but well, I guess it would be nicer if the conversion was made by the pymavlink module :):

packed = struct.pack("i", value)
value_f = struct.unpack("f", packed)[0]
# Send parameter set command
connection.param_set_send(
    param, value_f, mavutil.mavlink.MAV_PARAM_TYPE_INT32
)

damien-robotsix avatar May 16 '24 17:05 damien-robotsix