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

AP_MISSION: Add nan mission sanity checks to various mission commands #24701

Open
wants to merge 9 commits into
base: master
Choose a base branch
from

Conversation

trolledbypro
Copy link
Contributor

@trolledbypro trolledbypro commented Aug 18, 2023

In support of #24691
Hello,
As I continue to troubleshoot ArduPilot compatibility with MAVSDK Mission module, I noticed that several camera action commands did not have proper NaN support. ArduPilot was rejecting what are valid commands according to Mavlink due to invalid parameters:

MAV_CMD_IMAGE_STOP_CAPTURE:
Params 2, 3 and 4 can be set to NaN. Since these are reserved commands, their values are not saved to EEPROM and having these params as NaN has no effect.

MAV_CMD_VIDEO_START_CAPTURE:
Params 3 and 4 can be set to NaN. Since these are reserved commands, their values are not saved to EEPROM and having these params as NaN has no effect.

MAV_CMD_VIDEO_STOP_CAPTURE:
Params 2, 3 and 4 can be set to NaN. Since these are reserved commands, their values are not saved to EEPROM and having these params as NaN has no effect.

MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
Params 1, 2, 3 and 4 can be set to NaN. This command is special as commands stored to EEPROM can be NaN. To address this, I wrote the sanity check in a way that only accepts the following three cases:

  1. Both angles are defined and both turn rates are NaN
  2. Both angles are NaN and both turn rates are defined
  3. All angles and turn rates are defined, angles will be set and turn rates will be ignored

These three cases are consistent with the implementation in AP_Mount #23053.

In terms of testing, the only testing I have done is in ArduPilot SITL is to see if the commands are accepted. I have not tested with real hardware.

Co-authored-by: Nick Exton <NExton@sypaq.com.au>
packet.param3 = cmd.content.gimbal_manager_pitchyaw.pitch_rate_degs;
packet.param4 = cmd.content.gimbal_manager_pitchyaw.yaw_rate_degs;
case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
packet.param1 = (fabs(packet.param1 - INT8_MAX) < FLT_EPSILON) ? NAN : cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

AFAICS packet.param1 will always be zero here, so checking it for any other value makes no sense.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I corrected the issue in my newest commit

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.

3 participants