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

Rover: reject position targets if acceleration supplied #28076

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

Conversation

peterbarker
Copy link
Contributor

Replaces https://github.com/ArduPilot/ardupilot/pull/26955/files which simply factored the check out.

This both factors the check out and stops us accepting the position target if acceleration is set.

We should probably also reject if other bits and pieces are set.

@rmackay9
Copy link
Contributor

Thanks @peterbarker for this. I guess this has been tested in some way?

@peterbarker
Copy link
Contributor Author

Board                    AP_Periph  blimp  bootloader  copter  heli  iofirmware  plane  rover  sub
CubeOrange-periph-heavy  *                                                                     
Durandal                            *      *           *       *                 *      -24    *
Hitec-Airspeed           *                                                                     
KakuteH7-bdshot                     *      *           *       *                 *      8      *
MatekF405                           *      *           *       *                 *      0      *
Pixhawk1-1M-bdshot                  *                  *       *                 *      0      *
f103-QiotekPeriph        *                                                                     
f303-Universal           *                                                                     
iomcu                                                                *                         
revo-mini                           *      *           *       *                 *      0      *
skyviper-v2450                                         *                                       

@peterbarker
Copy link
Contributor Author

Tested in SITL with these commands:

# this one should move the vehicle:
# message set_position_target_local_ned 0 1 1 1 0b1111111111111000 10 10 0 0 0 0 0 0 0 0 0

# this one should be ignored as acceleration is supplied along with position:
# message set_position_target_local_ned 0 1 1 1 0b1111111000111000 10 10 0 0 0 0 0 0 0 0 0

# should work:
# message set_position_target_global_int 0 1 1 0 0b1111111111111000 -353630399 1491652946 0 0 0 0 0 0 0 0 0 

# acceleration not ignored:
# message set_position_target_global_int 0 1 1 0 0b1111111000111000 -353630399 1491652946 0 0 0 0 0 0 0 0 0 

(and gdb and breakpoints)

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

We discussed on the dev call and decided that we should add some text feedback to the user if their message is rejected because it's malformed

@Ryanf55
Copy link
Collaborator

Ryanf55 commented Sep 17, 2024

Relates to #23430 which has the same inability to share errors back to users for silently dropping invalid commands

…masked

Co-authored-by: muramura <[email protected]>

we don't use acceleration if you're trying to move the vehicle, so we shouldn't accept the command it isn't in the "ignore" mask
… masked

Co-authored-by: muramura <[email protected]>

we don't use acceleration if you're trying to move the vehicle, so we shouldn't accept the command it isn't in the "ignore" mask
@peterbarker peterbarker force-pushed the pr/reject-position-with-acceleration branch from d66e98c to 4be35cf Compare September 17, 2024 11:37
@peterbarker
Copy link
Contributor Author

As requested:

GUIDED> message set_position_target_global_int 0 1 1 0 0b1111111000111000 -353630399 1491652946 0 0 0 0 0 0 0 0 0 
GUIDED> AP: Ignoring SET_POSITION_TARGET_GLOBAL_INT; set ACC_IGNORE in mask

@@ -845,6 +845,11 @@ void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
}
}

void GCS_MAVLINK_Rover::send_acc_ignore_must_be_set_message(const char *msgname)
Copy link
Contributor

Choose a reason for hiding this comment

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

sorry to be annoying but can you add a comment above the method? Just copying the method from the .h is fine.

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

after the comment update, feel free to merge, thanks!

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

Successfully merging this pull request may close these issues.

4 participants