-
Notifications
You must be signed in to change notification settings - Fork 17.8k
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: implement external control #25204
Merged
peterbarker
merged 1 commit into
ArduPilot:master
from
srmainwaring:prs/pr-rover-external-control
Oct 24, 2023
Merged
Changes from all commits
Commits
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,37 @@ | ||
/* | ||
external control library for rover | ||
*/ | ||
|
||
|
||
#include "AP_ExternalControl_Rover.h" | ||
#if AP_EXTERNAL_CONTROL_ENABLED | ||
|
||
#include "Rover.h" | ||
|
||
/* | ||
set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw | ||
velocity is in earth frame, NED, m/s | ||
*/ | ||
bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) | ||
{ | ||
if (!ready_for_external_control()) { | ||
return false; | ||
} | ||
|
||
// rover is commanded in body-frame using FRD convention | ||
auto &ahrs = AP::ahrs(); | ||
Vector3f linear_velocity_body = ahrs.earth_to_body(linear_velocity); | ||
|
||
const float target_speed = linear_velocity_body.x; | ||
const float turn_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100; | ||
|
||
rover.mode_guided.set_desired_turn_rate_and_speed(turn_rate_cds, target_speed); | ||
return true; | ||
} | ||
|
||
bool AP_ExternalControl_Rover::ready_for_external_control() | ||
{ | ||
return rover.control_mode->in_guided_mode() && rover.arming.is_armed(); | ||
} | ||
|
||
#endif // AP_EXTERNAL_CONTROL_ENABLED |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,26 @@ | ||
/* | ||
external control library for rover | ||
*/ | ||
#pragma once | ||
|
||
#include <AP_ExternalControl/AP_ExternalControl.h> | ||
|
||
#if AP_EXTERNAL_CONTROL_ENABLED | ||
|
||
class AP_ExternalControl_Rover : public AP_ExternalControl { | ||
public: | ||
/* | ||
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. | ||
Velocity is in earth frame, NED [m/s]. | ||
Yaw is in earth frame, NED [rad/s]. | ||
*/ | ||
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override; | ||
private: | ||
/* | ||
Return true if Rover is ready to handle external control data. | ||
Currently checks mode and arm states. | ||
*/ | ||
bool ready_for_external_control(); | ||
}; | ||
|
||
#endif // AP_EXTERNAL_CONTROL_ENABLED |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Could add
WARN_IF_UNUSED
for these two functionsThere was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Could do. They're not marked as such in the Copter implementation of external control. What's the recommended house style for adding these attributes?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'd add them to Copter, perhaps in a separate PR. It's just additional compile-time-safety, not critical or a blocker.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ok - maybe we could do as a follow up in both cases to keep things consistent.