Skip to content

Commit

Permalink
Merge pull request #2534 from saihv/PR/control_fov
Browse files Browse the repository at this point in the history
simSetCameraFov() API to control FoV dynamically
  • Loading branch information
madratman authored Apr 8, 2020
2 parents fc87334 + 4c9a6f4 commit 0505f46
Show file tree
Hide file tree
Showing 10 changed files with 50 additions and 2 deletions.
1 change: 1 addition & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ class RpcLibClientBase {

CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const;
void simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name = "");
void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = "");

msr::airlib::Kinematics::State simGetGroundTruthKinematics(const std::string& vehicle_name = "") const;
msr::airlib::Environment::State simGetGroundTruthEnvironment(const std::string& vehicle_name = "") const;
Expand Down
1 change: 1 addition & 0 deletions AirLib/include/api/VehicleSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject {

virtual CameraInfo getCameraInfo(const std::string& camera_name) const = 0;
virtual void setCameraOrientation(const std::string& camera_name, const Quaternionr& orientation) = 0;
virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) = 0;

virtual CollisionInfo getCollisionInfo() const = 0;
virtual int getRemoteControlID() const = 0; //which RC to use, 0 is first one, -1 means disable RC (use keyborad)
Expand Down
4 changes: 4 additions & 0 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,6 +363,10 @@ void RpcLibClientBase::simSetCameraOrientation(const std::string& camera_name, c
{
pimpl_->client.call("simSetCameraOrientation", camera_name, RpcLibAdapatorsBase::Quaternionr(orientation), vehicle_name);
}
void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name)
{
pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name);
}

msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const
{
Expand Down
6 changes: 5 additions & 1 deletion AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,6 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
pimpl_->server.bind("armDisarm", [&](bool arm, const std::string& vehicle_name) -> bool {
return getVehicleApi(vehicle_name)->armDisarm(arm);
});

pimpl_->server.bind("simGetImages", [&](const std::vector<RpcLibAdapatorsBase::ImageRequest>& request_adapter, const std::string& vehicle_name) ->
vector<RpcLibAdapatorsBase::ImageResponse> {
const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter));
Expand Down Expand Up @@ -230,6 +229,11 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
getVehicleSimApi(vehicle_name)->setCameraOrientation(camera_name, orientation.to());
});

pimpl_->server.bind("simSetCameraFov", [&](const std::string& camera_name, float fov_degrees,
const std::string& vehicle_name) -> void {
getVehicleSimApi(vehicle_name)->setCameraFoV(camera_name, fov_degrees);
});

pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::CollisionInfo {
const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo();
return RpcLibAdapatorsBase::CollisionInfo(collision_info);
Expand Down
20 changes: 20 additions & 0 deletions PythonClient/airsim/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -153,8 +153,28 @@ def simGetCameraInfo(self, camera_name, vehicle_name = ''):
return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name))

def simSetCameraOrientation(self, camera_name, orientation, vehicle_name = ''):
"""
- Control the orientation of a selected camera
Args:
camera_name (str): Name of the camera to be controlled
orientation (airsim.Quaternion()): Quaternion representing the desired orientation of the camera
vehicle_name (str, optional): Name of vehicle which the camera corresponds to
"""
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
self.client.call('simSetCameraOrientation', str(camera_name), orientation, vehicle_name)

def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = ''):
"""
- Control the field of view of a selected camera
Args:
camera_name (str): Name of the camera to be controlled
fov_degrees (float): Value of field of view in degrees
vehicle_name (str, optional): Name of vehicle which the camera corresponds to
"""
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
return self.client.call('simSetCameraFov', str(camera_name), fov_degrees, vehicle_name)

def simGetGroundTruthKinematics(self, vehicle_name = ''):
kinematics_state = self.client.call('simGetGroundTruthKinematics', vehicle_name)
Expand Down
9 changes: 9 additions & 0 deletions Unreal/Plugins/AirSim/Source/PIPCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,15 @@ void APIPCamera::setCameraOrientation(const FRotator& rotator)
this->SetActorRelativeRotation(rotator);
}

void APIPCamera::setCameraFoV(float fov_degrees)
{
int image_count = static_cast<int>(Utils::toNumeric(ImageType::Count));
for (int image_type = 0; image_type < image_count; ++image_type) {
captures_[image_type]->FOVAngle = fov_degrees;
}
}


void APIPCamera::setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform)
{
//TODO: should we be ignoring position and orientation settings here?
Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/PIPCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ class AIRSIM_API APIPCamera : public ACameraActor
bool getCameraTypeEnabled(ImageType type) const;
void setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform);
void setCameraOrientation(const FRotator& rotator);
void setCameraFoV(float fov_degrees);

msr::airlib::ProjectionMatrix getProjectionMatrix(const APIPCamera::ImageType image_type) const;

Expand Down
8 changes: 8 additions & 0 deletions Unreal/Plugins/AirSim/Source/PawnSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,6 +412,14 @@ void PawnSimApi::setCameraOrientation(const std::string& camera_name, const msr:
}, true);
}

void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees)
{
UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, fov_degrees]() {
APIPCamera* camera = getCamera(camera_name);
camera->setCameraFoV(fov_degrees);
}, true);
}

//parameters in NED frame
PawnSimApi::Pose PawnSimApi::getPose() const
{
Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/PawnSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase {
virtual void setPose(const Pose& pose, bool ignore_collision) override;
virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override;
virtual void setCameraOrientation(const std::string& camera_name, const Quaternionr& orientation) override;
virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override;
virtual CollisionInfo getCollisionInfo() const override;
virtual int getRemoteControlID() const override;
virtual msr::airlib::RCData getRCData() const override;
Expand Down
1 change: 0 additions & 1 deletion Unreal/Plugins/AirSim/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,6 @@ std::vector<std::string> WorldSimApi::listSceneObjects(const std::string& name_r
return result;
}


WorldSimApi::Pose WorldSimApi::getObjectPose(const std::string& object_name) const
{
Pose result;
Expand Down

0 comments on commit 0505f46

Please sign in to comment.