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

Dds yaw control plane #26143

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

Conversation

Ryanf55
Copy link
Collaborator

@Ryanf55 Ryanf55 commented Feb 5, 2024

Purpose

Add lower level controls ability for turn rate on Plane when using DDS that isn't tied to a waypoint loiter (ideally).

Usage

ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019
./Tools/autotest/sim_vehicle.py -v ArduPlane -DG --console --enable-dds --ma
arm throttle
mode takeoff
mode guided
ros2 topic pub /ap/cmd_vel geometry_msgs/msg/TwistStamped "{header: {frame_id: base_link}, twist: {linear: {x: .nan, y: .nan, z: .nan}, angular: {z: -0.01}}}" --once

Problem

Seems like the navigation mode is overriding the lower level commands. I need to find a way to bypass it. Tips are appreciated.
Edit: It was suggested to make a patch to mode_guided if the yaw is set, then L1 needs to be bypassed. This wasn't necessary, it was an unrelated scaling issue.

Related

https://github.com/mavlink/mavlink/pull/2020/files#diff-9ef151b30f09d6d4f130434d941db479c3411ec15eca23580c5587b2c3b59ecdR5609

Mavlink body yaw rate

https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET


/*
Sets only the target yaw rate
Yaw is in earth frame, NED [rad/s]
Copy link
Contributor

Choose a reason for hiding this comment

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

i'd like a comment on what the intention is with coordinated turns. I would expected we would implement it with roll and coordinated

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

"A configured yaw rate of 2* pi / 30 will result in a complete circle in 30 seconds."

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

I would have expected the loiter center to also be re-set when the command is sent. Depending on the turn direction the center would be to the left or right of the current location by the loiter radius.


const auto direction_is_ccw = yaw_rate < 0;
if (!is_zero(yaw_rate)) {
auto const speed = plane.ahrs.groundspeed();
Copy link
Member

Choose a reason for hiding this comment

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

Using ground speed here might result in funny shape circles in wind, but maybe that is OK.

Copy link
Member

Choose a reason for hiding this comment

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

In-fact, set_radius_and_direction does not change the center of the loiter point, so it might do quite odd things.

@@ -366,6 +366,12 @@ bool Vector3<T>::is_nan(void) const
return isnan(x) || isnan(y) || isnan(z);
}

template <typename T>
bool Vector3<T>::is_all_nan(void) const
Copy link
Contributor

Choose a reason for hiding this comment

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

I feel like this begs to have a ::is_any_nan() too

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

Successfully merging this pull request may close these issues.

5 participants