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: implement external control #25204

Merged
Merged
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
37 changes: 37 additions & 0 deletions Rover/AP_ExternalControl_Rover.cpp
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
26 changes: 26 additions & 0 deletions Rover/AP_ExternalControl_Rover.h
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();
Copy link
Collaborator

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 functions

Copy link
Contributor Author

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?

Copy link
Collaborator

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.

Copy link
Contributor Author

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.

};

#endif // AP_EXTERNAL_CONTROL_ENABLED
9 changes: 6 additions & 3 deletions Rover/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include <AP_Follow/AP_Follow_config.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_EXTERNAL_CONTROL_ENABLED
#include <AP_ExternalControl/AP_ExternalControl.h>
#include "AP_ExternalControl_Rover.h"
#endif

// Configuration
Expand Down Expand Up @@ -83,6 +83,9 @@ class Rover : public AP_Vehicle {
friend class AP_Arming_Rover;
#if ADVANCED_FAILSAFE == ENABLED
friend class AP_AdvancedFailsafe_Rover;
#endif
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Rover;
#endif
friend class GCS_Rover;
friend class Mode;
Expand Down Expand Up @@ -147,9 +150,9 @@ class Rover : public AP_Vehicle {
// Arming/Disarming management class
AP_Arming_Rover arming;

// dummy external control implementation
// external control implementation
#if AP_EXTERNAL_CONTROL_ENABLED
AP_ExternalControl external_control;
AP_ExternalControl_Rover external_control;
#endif

#if AP_OPTICALFLOW_ENABLED
Expand Down
3 changes: 3 additions & 0 deletions Rover/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -488,6 +488,9 @@ class ModeCircle : public Mode
class ModeGuided : public Mode
{
public:
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Rover;
#endif

Number mode_number() const override { return Number::GUIDED; }
const char *name4() const override { return "GUID"; }
Expand Down