Copter: rename chase to follow

This commit is contained in:
Randy Mackay 2018-02-06 11:44:05 +09:00
parent 053983eb70
commit 6ee101ca98
6 changed files with 17 additions and 16 deletions

View File

@ -976,11 +976,11 @@ private:
#if MODE_CIRCLE_ENABLED == ENABLED
ModeCircle mode_circle;
#endif
ModeChase mode_chase;
#if MODE_DRIFT_ENABLED == ENABLED
ModeDrift mode_drift;
#endif
ModeFlip mode_flip;
ModeFollow mode_follow;
#if MODE_GUIDED_ENABLED == ENABLED
ModeGuided mode_guided;
#endif

View File

@ -47,7 +47,7 @@ NOINLINE void Copter::send_heartbeat(mavlink_channel_t chan)
case RTL:
case LOITER:
case AVOID_ADSB:
case CHASE:
case FOLLOW:
case GUIDED:
case CIRCLE:
case POSHOLD:

View File

@ -109,7 +109,7 @@ enum control_mode_t {
GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder
CHASE = 23, // chase attempts to follow a mavink system id
FOLLOW = 23, // follow attempts to follow another vehicle or ground station
};
enum mode_reason_t {

View File

@ -56,10 +56,6 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
break;
#endif
case CHASE:
ret = &mode_chase;
break;
#if MODE_CIRCLE_ENABLED == ENABLED
case CIRCLE:
ret = &mode_circle;
@ -150,6 +146,10 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
break;
#endif
case FOLLOW:
ret = &mode_follow;
break;
default:
break;
}

View File

@ -1067,6 +1067,7 @@ private:
};
// modes below rely on Guided mode so must be declared at the end (instead of in alphabetical order)
class ModeAvoidADSB : public ModeGuided {
@ -1093,11 +1094,11 @@ private:
};
class ModeChase : public ModeGuided {
class ModeFollow : public ModeGuided {
public:
ModeChase(Copter &copter) :
ModeFollow(Copter &copter) :
Copter::ModeGuided(copter) {
}
@ -1113,6 +1114,6 @@ public:
protected:
const char *name() const override { return "CHASE"; }
const char *name4() const override { return "CHAS"; }
const char *name() const override { return "FOLLOW"; }
const char *name4() const override { return "FOLL"; }
};

View File

@ -1,7 +1,7 @@
#include "Copter.h"
/*
* mode_chase.cpp - chase another mavlink-enabled vehicle by system id
* mode_follow.cpp - follow another mavlink-enabled vehicle by system id
*
* TODO: set ROI yaw mode / point camera at target
* TODO: stick control to move around on sphere
@ -19,23 +19,23 @@
#endif
// initialise avoid_adsb controller
bool Copter::ModeChase::init(const bool ignore_checks)
bool Copter::ModeFollow::init(const bool ignore_checks)
{
// re-use guided mode
return Copter::ModeGuided::init(ignore_checks);
}
bool Copter::ModeChase::set_velocity(const Vector3f& velocity_neu)
bool Copter::ModeFollow::set_velocity(const Vector3f& velocity_neu)
{
// check flight mode
if (_copter.flightmode != &_copter.mode_chase) {
if (_copter.flightmode != &_copter.mode_follow) {
return false;
}
return true;
}
void Copter::ModeChase::run()
void Copter::ModeFollow::run()
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {