diff --git a/AirLib/include/vehicles/multirotor/api/MultirotorApi.hpp b/AirLib/include/vehicles/multirotor/api/MultirotorApi.hpp index d24eeb2d93..1de732384f 100644 --- a/AirLib/include/vehicles/multirotor/api/MultirotorApi.hpp +++ b/AirLib/include/vehicles/multirotor/api/MultirotorApi.hpp @@ -18,7 +18,7 @@ using namespace msr::airlib; namespace msr { namespace airlib { -// We want to make it possible for MultirotorRpcLibClient to call the offboard movement methods (moveByAngle, moveByVelocity, etc) at a high +// We want to make it possible for MultirotorRpcLibClient to call the offboard movement methods (moveByAngleZ, moveByVelocity, etc) at a high // rate, like 30 times a second. But we also want these movement methods to drive the drone at a reliable rate which we do inside // DroneControllerBase using the Waiter object so it pumps the virtual commandVelocity method at a fixed rate defined by getCommandPeriod. // This fixed rate is needed by the drone flight controller (for example PX4) because the flight controller usually reverts to @@ -83,9 +83,9 @@ class MultirotorApi : public VehicleApiBase { return controller_->goHome(*pending_); } - bool moveByAngle(float pitch, float roll, float z, float yaw, float duration) + bool moveByAngleZ(float pitch, float roll, float z, float yaw, float duration) { - std::shared_ptr cmd = std::make_shared(controller_, pitch, roll, z, yaw, duration); + std::shared_ptr cmd = std::make_shared(controller_, pitch, roll, z, yaw, duration); return enqueueCommand(cmd); } @@ -384,10 +384,10 @@ class MultirotorApi : public VehicleApiBase { return true; } - class MoveByAngle : public OffboardCommand { + class MoveByAngleZ : public OffboardCommand { float pitch_, roll_, z_, yaw_, duration_; public: - MoveByAngle(DroneControllerBase* controller, float pitch, float roll, float z, float yaw, float duration) : OffboardCommand(controller) { + MoveByAngleZ(DroneControllerBase* controller, float pitch, float roll, float z, float yaw, float duration) : OffboardCommand(controller) { this->pitch_ = pitch; this->roll_ = roll; this->z_ = z; @@ -395,7 +395,7 @@ class MultirotorApi : public VehicleApiBase { this->duration_ = duration; } virtual void executeImpl(DroneControllerBase* controller, CancelableBase& cancelable) override { - controller->moveByAngle(pitch_, roll_, z_, yaw_, duration_, cancelable); + controller->moveByAngleZ(pitch_, roll_, z_, yaw_, duration_, cancelable); } }; diff --git a/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibClient.hpp b/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibClient.hpp index fe2d6a9b1f..e09a577ed9 100644 --- a/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibClient.hpp +++ b/AirLib/include/vehicles/multirotor/api/MultirotorRpcLibClient.hpp @@ -23,7 +23,7 @@ class MultirotorRpcLibClient : public RpcLibClientBase { bool takeoff(float max_wait_ms = 15); bool land(float max_wait_seconds = 60); bool goHome(); - bool moveByAngle(float pitch, float roll, float z, float yaw, float duration); + bool moveByAngleZ(float pitch, float roll, float z, float yaw, float duration); bool moveByVelocity(float vx, float vy, float vz, float duration, DrivetrainType drivetrain = DrivetrainType::MaxDegreeOfFreedom, const YawMode& yaw_mode = YawMode()); diff --git a/AirLib/include/vehicles/multirotor/controllers/DroneControllerBase.hpp b/AirLib/include/vehicles/multirotor/controllers/DroneControllerBase.hpp index 0747f97491..445c36700a 100644 --- a/AirLib/include/vehicles/multirotor/controllers/DroneControllerBase.hpp +++ b/AirLib/include/vehicles/multirotor/controllers/DroneControllerBase.hpp @@ -102,10 +102,10 @@ class DroneControllerBase : public VehicleControllerBase { /// make the drone move forwards, a little bit of roll can make it move sideways. The yaw control can /// make the drone spin around on the spot. The duration says how long you want to apply these settings /// before reverting to a hover command. So you can say "fly forwards slowly for 1 second" using - /// moveByAngle(0.1, 0, z, yaw, 1, ...). The cancelable_action can be used to canel all actions. In fact, + /// moveByAngleZ(0.1, 0, z, yaw, 1, ...). The cancelable_action can be used to canel all actions. In fact, /// every time you call another move* method you will automatically cancel any previous action that is /// happening. - virtual bool moveByAngle(float pitch, float roll, float z, float yaw, float duration + virtual bool moveByAngleZ(float pitch, float roll, float z, float yaw, float duration , CancelableBase& cancelable_action); diff --git a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp index 41ddf38faa..529130cd72 100644 --- a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp +++ b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibClient.cpp @@ -61,9 +61,9 @@ bool MultirotorRpcLibClient::goHome() return static_cast(getClient())->call("goHome").as(); } -bool MultirotorRpcLibClient::moveByAngle(float pitch, float roll, float z, float yaw, float duration) +bool MultirotorRpcLibClient::moveByAngleZ(float pitch, float roll, float z, float yaw, float duration) { - return static_cast(getClient())->call("moveByAngle", pitch, roll, z, yaw, duration).as(); + return static_cast(getClient())->call("moveByAngleZ", pitch, roll, z, yaw, duration).as(); } bool MultirotorRpcLibClient::moveByVelocity(float vx, float vy, float vz, float duration, DrivetrainType drivetrain, const YawMode& yaw_mode) diff --git a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp index 7c2afc305b..2c7829c1f8 100644 --- a/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp +++ b/AirLib/src/vehicles/multirotor/api/MultirotorRpcLibServer.cpp @@ -46,8 +46,8 @@ MultirotorRpcLibServer::MultirotorRpcLibServer(MultirotorApi* drone, string serv (static_cast(getServer()))-> - bind("moveByAngle", [&](float pitch, float roll, float z, float yaw, float duration) -> - bool { return getDroneApi()->moveByAngle(pitch, roll, z, yaw, duration); }); + bind("moveByAngleZ", [&](float pitch, float roll, float z, float yaw, float duration) -> + bool { return getDroneApi()->moveByAngleZ(pitch, roll, z, yaw, duration); }); (static_cast(getServer()))-> bind("moveByVelocity", [&](float vx, float vy, float vz, float duration, DrivetrainType drivetrain, const MultirotorRpcLibAdapators::YawMode& yaw_mode) -> bool { return getDroneApi()->moveByVelocity(vx, vy, vz, duration, drivetrain, yaw_mode.to()); }); diff --git a/AirLib/src/vehicles/multirotor/controllers/DroneControllerBase.cpp b/AirLib/src/vehicles/multirotor/controllers/DroneControllerBase.cpp index c10595dd15..07c06b9f13 100644 --- a/AirLib/src/vehicles/multirotor/controllers/DroneControllerBase.cpp +++ b/AirLib/src/vehicles/multirotor/controllers/DroneControllerBase.cpp @@ -46,7 +46,7 @@ void DroneControllerBase::loopCommandPost() //no-op by default. derived class can override it if needed } -bool DroneControllerBase::moveByAngle(float pitch, float roll, float z, float yaw, float duration +bool DroneControllerBase::moveByAngleZ(float pitch, float roll, float z, float yaw, float duration , CancelableBase& cancelable_action) { if (duration <= 0) diff --git a/DroneShell/src/main.cpp b/DroneShell/src/main.cpp index 5e2cc27452..12b28b2c17 100644 --- a/DroneShell/src/main.cpp +++ b/DroneShell/src/main.cpp @@ -482,9 +482,9 @@ class MoveByManualCommand : public DroneCommand { }; -class MoveByAngleCommand : public DroneCommand { +class MoveByAngleZCommand : public DroneCommand { public: - MoveByAngleCommand() : DroneCommand("MoveByAngle", "Move with specified roll and pitch, leaving z as-is") + MoveByAngleZCommand() : DroneCommand("MoveByAngleZ", "Move with specified roll and pitch, leaving z as-is") { this->addSwitch({"-pitch", "0", "pitch angle in degrees (default 0)" }); this->addSwitch({"-roll", "0", "roll angle in degrees (default 0)" }); @@ -503,7 +503,7 @@ class MoveByAngleCommand : public DroneCommand { CommandContext* context = params.context; context->tasker.execute([=]() { - context->client.moveByAngle(pitch, roll, z, yaw, duration); + context->client.moveByAngleZ(pitch, roll, z, yaw, duration); }); return false; @@ -662,12 +662,12 @@ class BackForthByAngleCommand : public DroneCommand { CommandContext* context = params.context; context->tasker.execute([=]() { - if (!context->client.moveByAngle(pitch, roll, z, yaw, duration)) { + if (!context->client.moveByAngleZ(pitch, roll, z, yaw, duration)) { throw std::runtime_error("BackForthByAngleCommand cancelled"); } context->client.hover(); context->sleep_for(pause_time); - if (!context->client.moveByAngle(-pitch, -roll, z, yaw, duration)){ + if (!context->client.moveByAngleZ(-pitch, -roll, z, yaw, duration)){ throw std::runtime_error("BackForthByAngleCommand cancelled"); } }, iterations); @@ -747,22 +747,22 @@ class SquareByAngleCommand : public DroneCommand { CommandContext* context = params.context; context->tasker.execute([=]() { - if (!context->client.moveByAngle(pitch, -roll, z, yaw, 0)) { + if (!context->client.moveByAngleZ(pitch, -roll, z, yaw, 0)) { throw std::runtime_error("SquareByAngleCommand cancelled"); } context->client.hover(); context->sleep_for(pause_time); - if (!context->client.moveByAngle(-pitch, -roll, z, yaw, 0)) { + if (!context->client.moveByAngleZ(-pitch, -roll, z, yaw, 0)) { throw std::runtime_error("SquareByAngleCommand cancelled"); } context->client.hover(); context->sleep_for(pause_time); - if (!context->client.moveByAngle(-pitch, roll, z, yaw, 0)) { + if (!context->client.moveByAngleZ(-pitch, roll, z, yaw, 0)) { throw std::runtime_error("SquareByAngleCommand cancelled"); } context->client.hover(); context->sleep_for(pause_time); - if (!context->client.moveByAngle(-pitch, -roll, z, yaw, 0)){ + if (!context->client.moveByAngleZ(-pitch, -roll, z, yaw, 0)){ throw std::runtime_error("SquareByAngleCommand cancelled"); } context->client.hover(); @@ -1351,7 +1351,7 @@ int main(int argc, const char *argv[]) { MoveToPositionCommand moveToPosition; GetPositionCommand getPosition; MoveByManualCommand moveByManual; - MoveByAngleCommand moveByAngle; + MoveByAngleZCommand moveByAngleZ; MoveByVelocityCommand moveByVelocity; MoveByVelocityZCommand moveByVelocityZ; MoveOnPathCommand moveOnPath; @@ -1383,7 +1383,7 @@ int main(int argc, const char *argv[]) { shell.addCommand(hover); shell.addCommand(moveToPosition); shell.addCommand(moveByManual); - shell.addCommand(moveByAngle); + shell.addCommand(moveByAngleZ); shell.addCommand(moveByVelocity); shell.addCommand(moveByVelocityZ); shell.addCommand(moveOnPath); diff --git a/PythonClient/AirSimClient.py b/PythonClient/AirSimClient.py index b6f689dca8..787571e054 100644 --- a/PythonClient/AirSimClient.py +++ b/PythonClient/AirSimClient.py @@ -547,8 +547,8 @@ def getServerDebugInfo(self): # APIs for control - def moveByAngle(self, pitch, roll, z, yaw, duration): - return self.client.call('moveByAngle', pitch, roll, z, yaw, duration) + def moveByAngleZ(self, pitch, roll, z, yaw, duration): + return self.client.call('moveByAngleZ', pitch, roll, z, yaw, duration) def moveByVelocity(self, vx, vy, vz, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode()): return self.client.call('moveByVelocity', vx, vy, vz, duration, drivetrain, yaw_mode)