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

Bug Found in msgID #332 mavlink protocol BOF #18369

Closed
BOB4Drone opened this issue Oct 6, 2021 · 4 comments · Fixed by #18371
Closed

Bug Found in msgID #332 mavlink protocol BOF #18369

BOB4Drone opened this issue Oct 6, 2021 · 4 comments · Fixed by #18371

Comments

@BOB4Drone
Copy link

BOB4Drone commented Oct 6, 2021

Steps to reproduce the behavior:

  1. Turn the drone on
  2. Set the lower one byte to be greater than 0x75 except for the CRC of the MAVLINK PROTOCOL packet which is msgID 332
  3. Send a packet set as a serial port to the drone.
  4. BOF crash occurs.

example msgID332 packet

fdef0000d2ff004c010003a8ba951e05809b5f1b8c9069167f55c709ad76837e1a585c22264e6a3785ce716070b9ee1954a849e718eb9bb2bdcc21a27d7c75075d3553250d12b7abd7c267c91e2c31ad1e0ce5fc3fd0403c104fb304935a8fa5b399a70fa94b5fcebdafc4cd0dc0c144dd8ddfd7cbea9c124490d4c80671cab01dce514f299b9598f8a193156c981097892bdead25a0b63e7572f73325bd05ff57911407eed28b44f339d09c945812a81661bf8cf633f5e1f4836f4bbea984c8a37e780b53fc9e93df755c224e40326a27e767c3279e3c19fc1af681cf0de9e14b3bbdf67646f2e783a9e2d506eb0354974f14c34c3a03777ad3b9

Describe the bug

The lower 1 byte of MAVLINK PROTOCOL with msgID number 332 is "valid_points".
We can set "valid_points" to a maximum of 0xff.
BOF occurs in the source code line below when "valid_points" is set to a large value.
I found it in sitl mode and also checked it on the drone board.

source code

https://github.com/PX4/PX4-Autopilot/blob/master/src/modules/mavlink/mavlink_receiver.cpp
PX4-Autopilot/src/modules/mavlink/mavlink_receiver.cpp (line 1942 ~ line 1944)

TEST board

px4_fmu-v5
nxp_fmuk66-v3

log file page

https://logs.px4.io/plot_app?log=1b47a1c3-3afe-4518-9628-f3284d67fb41

image

@dagar
Copy link
Member

dagar commented Oct 6, 2021

Thanks for reporting. It appears to be a slight discrepancy with the size difference of the uORB msg and mavlink.

MavlinkReceiver::handle_message_trajectory_representation_waypoints(mavlink_message_t *msg)
{
mavlink_trajectory_representation_waypoints_t trajectory;
mavlink_msg_trajectory_representation_waypoints_decode(msg, &trajectory);
vehicle_trajectory_waypoint_s trajectory_waypoint{};
trajectory_waypoint.timestamp = hrt_absolute_time();
const int number_valid_points = trajectory.valid_points;
for (int i = 0; i < vehicle_trajectory_waypoint_s::NUMBER_POINTS; ++i) {
trajectory_waypoint.waypoints[i].position[0] = trajectory.pos_x[i];
trajectory_waypoint.waypoints[i].position[1] = trajectory.pos_y[i];
trajectory_waypoint.waypoints[i].position[2] = trajectory.pos_z[i];
trajectory_waypoint.waypoints[i].velocity[0] = trajectory.vel_x[i];
trajectory_waypoint.waypoints[i].velocity[1] = trajectory.vel_y[i];
trajectory_waypoint.waypoints[i].velocity[2] = trajectory.vel_z[i];
trajectory_waypoint.waypoints[i].acceleration[0] = trajectory.acc_x[i];
trajectory_waypoint.waypoints[i].acceleration[1] = trajectory.acc_y[i];
trajectory_waypoint.waypoints[i].acceleration[2] = trajectory.acc_z[i];
trajectory_waypoint.waypoints[i].yaw = trajectory.pos_yaw[i];
trajectory_waypoint.waypoints[i].yaw_speed = trajectory.vel_yaw[i];
trajectory_waypoint.waypoints[i].type = UINT8_MAX;
}
for (int i = 0; i < number_valid_points; ++i) {
trajectory_waypoint.waypoints[i].point_valid = true;
}
for (int i = number_valid_points; i < vehicle_trajectory_waypoint_s::NUMBER_POINTS; ++i) {
trajectory_waypoint.waypoints[i].point_valid = false;
}
_trajectory_waypoint_pub.publish(trajectory_waypoint);
}

@dagar
Copy link
Member

dagar commented Oct 6, 2021

@BOB4Drone could you try #18371?

@BOB4Drone
Copy link
Author

Crash did not occur when tested on simulator and drone board.
It seems to have been fixed well.

@dagar
Copy link
Member

dagar commented Oct 6, 2021

Thanks for the quick test @BOB4Drone.

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 a pull request may close this issue.

2 participants