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

Fixedwing Add support for offboard velocity setpoints #18495

Merged
merged 2 commits into from
Jan 3, 2022

Conversation

Jaeyoung-Lim
Copy link
Member

@Jaeyoung-Lim Jaeyoung-Lim commented Oct 22, 2021

Describe problem solved by this pull request
Previously vehicles only supported position setpoints which were tracked using a L1 controller.

While this is sufficient to do waypoint navigation, it is hard do more advanced maneuvers using only a L1 position setpoint.

Describe your solution
This PR adds support for offboard velocity setpoints for fixedwing type vehicles. The velocity can be commanded in the local frame and the vehicle will try to follow the velocity setpoints in 3D.

  • The horizontal velocity vx, vy will be passed as the target groundspeed.
  • The vertical velocity vz will be mapped to TECS height rate setpoints

Being able to command velocity setpoints in the local frame allows fixedwing vehicles to be used in more robotics oriented tasks such as trajectory tracking, formation flying etc

Test data / coverage
Tested in SITL Gazebo with offboard setpoints sent by ROS

Additional context

@Jaeyoung-Lim Jaeyoung-Lim marked this pull request as ready for review October 22, 2021 10:24
Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

Seems fine beside that small comment on the yaw_setpoint.

@Jaeyoung-Lim Jaeyoung-Lim force-pushed the pr-fw-offboard-vel branch 2 times, most recently from 3d7798f to 1af2207 Compare November 7, 2021 14:08
@@ -757,6 +757,10 @@ FixedwingPositionControl::control_auto(const hrt_abstime &now, const Vector2d &c
control_auto_position(now, curr_pos, ground_speed, pos_sp_prev, pos_sp_curr);
break;

case position_setpoint_s::SETPOINT_TYPE_VELOCITY:
Copy link
Member

Choose a reason for hiding this comment

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

SETPOINT_TYPE_VELOCITY will be purged "soon". #18026

Copy link
Member Author

Choose a reason for hiding this comment

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

@dagar What would be the alternative to pass velocity setpoints? Should we move away from using position setpoint types all together? (Seems fw pos control is the only place this is being used)

Copy link
Member

Choose a reason for hiding this comment

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

I'm only talking about the position_setpoint_triplet coming from navigator. Everything else using the trajectory_setpoint is still valid.

@@ -896,6 +900,10 @@ FixedwingPositionControl::control_auto_descend(const hrt_abstime &now)
uint8_t
FixedwingPositionControl::handle_setpoint_type(const uint8_t setpoint_type, const position_setpoint_s &pos_sp_curr)
{
if (!_control_mode.flag_control_position_enabled && _control_mode.flag_control_velocity_enabled) {
return position_setpoint_s::SETPOINT_TYPE_VELOCITY;
Copy link
Member Author

Choose a reason for hiding this comment

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

@dagar We are not using SETPOINT_TYPE_VELOCITY from the navigator, but we still need SETPOINT_TYPE_VELOCITY in the fw position controller

Copy link
Member

Choose a reason for hiding this comment

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

If it's easy we can keep it for now, but we'll have to do something about it later.

Copy link
Member Author

Choose a reason for hiding this comment

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

@dagar I think this needs to be changed all together on moving away from position setpoint as a state machine for the position controller behavior

@Jaeyoung-Lim
Copy link
Member Author

@sfuhrer @dagar Any chance we can get this in?

This commit adds a velocity controller which the setpoint can be passed using offboard setpoints
@Jaeyoung-Lim
Copy link
Member Author

Jaeyoung-Lim commented Dec 30, 2021

@sfuhrer Rebased and addressed review comments!

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

Haven't tested offboard ever myself, but don't see any obvious issue here.

@Jaeyoung-Lim
Copy link
Member Author

@sfuhrer Thanks!

@lichishubao
Copy link

Which topic can control velocity, I used mavros/setpoint_raw/global send velocity message ,but it did not work.

@Jaeyoung-Lim
Copy link
Member Author

@lichishubao Please do not hijack the topic of this PR.

You can post a new issue or a question to the public forum

@lichishubao
Copy link

@lichishubao Please do not hijack the topic of this PR.

You can post a new issue or a question to the public forum

This is not my intention,I just want to know which offboard setpoints do you sent by ROS, I might have used the wrong topic

@Jaeyoung-Lim
Copy link
Member Author

@lichishubao Feel free to ask questions on the public forum, or on the px4 discord.

If you think it is relevant, you can also open a new issue

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