Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add integer bound check #28790

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

RamReso
Copy link

@RamReso RamReso commented Dec 1, 2024

When sending mavlink command_long messages with some arbitrary parameters, I noticed random crashes in the simulation. I looked into it and found, that the simulation always crashes, when I send a parameter >215 or <-215 for a coordinate. This was due to a integer over/underflow in the conversion from long to int.

I added the necessary checks to the converting function and now I do not longer notice the problem.

@tpwrules
Copy link
Contributor

tpwrules commented Dec 1, 2024

It is strange, but not impossible, that this should crash. What platform are you running on and what message are you trying to send?

The check needs to be moved to only be done if stores_location and after the multiplication (but before the cast).

@RamReso
Copy link
Author

RamReso commented Dec 2, 2024

I'm not 100% sure what you mean by platform. I'm only using a simulation which I start with:
python Tools/autotest/sim_vehicle.py -v ArduCopter -D

I encounter the problem if I send the command_long over mavlink using a self written python program with the following parameters:

target_system = 1
target_component = 1
command = 201 (MAV_CMD_DO_SET_ROI)
confirmation = 0
param_1= 841.8709017045903
param_2: -355.8708939554573
param_3: -487.38928814332417
param_4: -605.9047446662618
param_5: 409.52030363804556
param_6: -237.83399241328152
param_7: -691.756644619793 

These parameter values are random, but they should not lead to a crash.

I also noticed the same problems using different command, e.g. 195-MAV_CMD_DO_SET_ROI_LOCATION

The stack trace is the following:

convert_COMMAND_LONG_loc_param GCS_Common.cpp:5154
GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT GCS_Common.cpp:5174
GCS_MAVLINK::try_command_long_as_command_int GCS_Common.cpp:5140
GCS_MAVLINK::handle_command_long GCS_Common.cpp:5195
GCS_MAVLINK::handle_message GCS_Common.cpp:4271
GCS_MAVLINK_Copter::handle_message GCS_Mavlink.cpp:1523
GCS_MAVLINK::packetReceived GCS_Common.cpp:1835
GCS_MAVLINK_Copter::packetReceived GCS_Mavlink.cpp:646
GCS_MAVLINK::update_receive GCS_Common.cpp:1887
GCS::update_receive GCS_Common.cpp:2707
Functor<void>::method_wrapper<GCS, &GCS::update_receive> functor.h:88
Functor::operator() functor.h:54
AP_Scheduler::run AP_Scheduler.cpp:264
AP_Scheduler::loop AP_Scheduler.cpp:393
AP_Vehicle::loop AP_Vehicle.cpp:544
HAL_SITL::run HAL_SITL_Class.cpp:289
main Copter.cpp:957

Thank you for your recommendation regarding the position of the check. I will adjust the code accordingly.

@tpwrules
Copy link
Contributor

tpwrules commented Dec 2, 2024

Thanks for providing the command you used. By platform I mean processor type, operating system name and version, compiler name and version, etc. Ardupilot SITL is usually run on Ubuntu x86_64 so that's the least likely to cause problems.

Thanks also for updating the code, but there are a lot of casts in Ardupilot so it's concerning that this one should crash. This is undefined behavior so we are clearly in the wrong, but I'd like to be able to replicate the problem myself and better determine impact on common platforms and what other changes we might need to make.

@tpwrules
Copy link
Contributor

tpwrules commented Dec 2, 2024

Well I expected this to be a semi-exotic platform but sure enough it's easily triggerable on x86_64 (using my Nix flake). You can use mavproxy and the command module load message ; message COMMAND_LONG 1 1 201 0 841 -355 -487 -605 409 -237 -691 . Sure enough it takes a SIGFPE in convert_COMMAND_LONG_loc_param which causes the SITL to dump core and abort.

It also happens on a non-debug build (you selected a debug build with -D). It does not happen on ChibiOS (CubeOrange, non-debug build). It doesn't happen either on the linux target.

I will discuss this with the team and see if this is the right fix and if we need to do more.

@tridge
Copy link
Contributor

tridge commented Dec 2, 2024

I think @peterbarker should look at this, though I think the fix is correct. I would have used constrain_float() though.

@tridge
Copy link
Contributor

tridge commented Dec 2, 2024

Note that we deliberately ignore SIGFPE on non-SITL. If you want to see what a real flight controller would do in a situation like this then set "SIM_FLOAT_EXCEPT = 0" and SITL will ignore FPE in the same way a real flight controller does.
We deliberately deviate from the behaviour of a real flight controller by default in SITL to help us find cases like this.

@IamPete1
Copy link
Member

IamPete1 commented Dec 3, 2024

Much larger change, but we should probably reject the command in this case.

@RamReso
Copy link
Author

RamReso commented Dec 3, 2024

Done.

@RamReso
Copy link
Author

RamReso commented Dec 3, 2024

Much larger change, but we should probably reject the command in this case.

I agree with that. But I'm not sure if I can implement this by my own.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants