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

implement GUIDED_HEADING_TYPE default mavlink message #28527

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
21 changes: 15 additions & 6 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -863,6 +863,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com
if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) ||
(plane.control_mode == &plane.mode_guided)) {
plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND);
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
#endif

// add home alt if needed
if (requested_position.relative_alt) {
Expand Down Expand Up @@ -973,22 +976,28 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl

float new_target_heading = radians(wrap_180(packet.param2));

// course over ground
if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int
switch(HEADING_TYPE(packet.param1)) {
case HEADING_TYPE_COURSE_OVER_GROUND:
// course over ground
Copy link
Collaborator

Choose a reason for hiding this comment

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

I think it's safe to remove these comments, it's obvious from the case what this is for.

plane.guided_state.target_heading_type = GUIDED_HEADING_COG;
plane.prev_WP_loc = plane.current_loc;
// normal vehicle heading
} else if (int(packet.param1) == HEADING_TYPE_HEADING) { // compare as nearest int
break;
case HEADING_TYPE_HEADING:
// normal vehicle heading
plane.guided_state.target_heading_type = GUIDED_HEADING_HEADING;
} else {
break;
case HEADING_TYPE_DEFAULT:
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
return MAV_RESULT_ACCEPTED;
default:
// MAV_RESULT_DENIED means Command is invalid (is supported but has invalid parameters).
return MAV_RESULT_DENIED;
}

plane.g2.guidedHeading.reset_I();

plane.guided_state.target_heading = new_target_heading;
plane.guided_state.target_heading_accel_limit = MAX(packet.param3, 0.05f);
plane.guided_state.target_heading_accel_limit = MAX(is_zero(packet.param3)? 10.0f : packet.param3 , 10.0f); // the, previous limit of 0.05 was 0.29 degrees, not very useful
Copy link
Member

Choose a reason for hiding this comment

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

Why this change?

Copy link
Contributor Author

@timtuxworth timtuxworth Nov 7, 2024

Choose a reason for hiding this comment

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

As per the comment @IamPete // the, previous limit of 0.05 was 0.29 degrees, not very useful
It was throttling the rate at which heading would change to very, very tiny increments that prevented the follow from being able to track the target plane.

Copy link
Member

Choose a reason for hiding this comment

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

It's a max not a min, it's saying the lowest it can be is 0.05 but it can be larger.

plane.guided_state.target_heading_time_ms = AP_HAL::millis();
return MAV_RESULT_ACCEPTED;
}
Expand Down
2 changes: 1 addition & 1 deletion modules/mavlink
Loading