Skip to content

Commit

Permalink
Copter: Guard External Control with a define
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
  • Loading branch information
Ryanf55 committed Aug 10, 2023
1 parent 84a4942 commit bc92988
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 1 deletion.
7 changes: 6 additions & 1 deletion ArduCopter/AP_ExternalControl_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,11 @@
external control library for copter
*/

#include "Copter.h"

#include "AP_ExternalControl_Copter.h"
#if AP_EXTERNAL_CONTROL_ENABLED

#include "Copter.h"

/*
set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw
Expand All @@ -21,3 +24,5 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f
copter.mode_guided.set_velocity(velocity_up_cms, false, 0, !isnan(yaw_rate_rads), yaw_rate_cds);
return true;
}

#endif // AP_EXTERNAL_CONTROL_ENABLED
4 changes: 4 additions & 0 deletions ArduCopter/AP_ExternalControl_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

#include <AP_ExternalControl/AP_ExternalControl.h>

#if AP_EXTERNAL_CONTROL_ENABLED

class AP_ExternalControl_Copter : public AP_ExternalControl {
public:
/*
Expand All @@ -14,3 +16,5 @@ class AP_ExternalControl_Copter : public AP_ExternalControl {
*/
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override;
};

#endif // AP_EXTERNAL_CONTROL_ENABLED
9 changes: 9 additions & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,11 @@
#include "GCS_Copter.h"
#include "AP_Rally.h" // Rally point library
#include "AP_Arming.h"

#include <AP_ExternalControl/AP_ExternalControl_config.h>
#if AP_EXTERNAL_CONTROL_ENABLED
#include "AP_ExternalControl_Copter.h"
#endif

#include <AP_Beacon/AP_Beacon_config.h>
#if AP_BEACON_ENABLED
Expand Down Expand Up @@ -194,7 +198,9 @@ class Copter : public AP_Vehicle {
friend class AP_AdvancedFailsafe_Copter;
#endif
friend class AP_Arming_Copter;
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Copter;
#endif
friend class ToyMode;
friend class RC_Channel_Copter;
friend class RC_Channels_Copter;
Expand Down Expand Up @@ -322,7 +328,10 @@ class Copter : public AP_Vehicle {
#endif

// external control library
#if AP_EXTERNAL_CONTROL_ENABLED
AP_ExternalControl_Copter external_control;
#endif


// system time in milliseconds of last recorded yaw reset from ekf
uint32_t ekfYawReset_ms;
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include "Copter.h"
#include <AP_Math/chirp.h>
#include <AP_ExternalControl/AP_ExternalControl_config.h> // TODO why is this needed if Copter.h includes this
class Parameters;
class ParametersG2;

Expand Down Expand Up @@ -957,7 +958,10 @@ class ModeFlowHold : public Mode {
class ModeGuided : public Mode {

public:
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Copter;
#endif

// inherit constructor
using Mode::Mode;
Number mode_number() const override { return Number::GUIDED; }
Expand Down

0 comments on commit bc92988

Please sign in to comment.