Skip to content

Commit

Permalink
Upgrade setCameraOrientation to setCameraPose (#2710)
Browse files Browse the repository at this point in the history
* Upgrade setCameraOrientation to setCameraPose

* Added corresponding impl for Unity, updated documentation to reflect new func

* [Unity] Add SetPose implementation in DataCapture.cs

* [Pythonclient] Upgrade examples to simSetCameraPose

* [ros] Upgrade to setCameraPose

Co-authored-by: Sai Vemprala <[email protected]>
  • Loading branch information
rajat2004 and saihv authored Jul 22, 2020
1 parent a45d470 commit 040a08a
Show file tree
Hide file tree
Showing 25 changed files with 72 additions and 52 deletions.
2 changes: 1 addition & 1 deletion AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ class RpcLibClientBase {
CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const;

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 simSetCameraPose(const std::string& camera_name, const Pose& pose, 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;
Expand Down
2 changes: 1 addition & 1 deletion AirLib/include/api/VehicleSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject {
virtual const msr::airlib::Environment* getGroundTruthEnvironment() const = 0;

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

virtual CollisionInfo getCollisionInfo() const = 0;
Expand Down
4 changes: 2 additions & 2 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -364,9 +364,9 @@ CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, co
{
return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as<RpcLibAdapatorsBase::CameraInfo>().to();
}
void RpcLibClientBase::simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name)
void RpcLibClientBase::simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name)
{
pimpl_->client.call("simSetCameraOrientation", camera_name, RpcLibAdapatorsBase::Quaternionr(orientation), vehicle_name);
pimpl_->client.call("simSetCameraPose", camera_name, RpcLibAdapatorsBase::Pose(pose), vehicle_name);
}
void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name)
{
Expand Down
4 changes: 2 additions & 2 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,9 +229,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
return RpcLibAdapatorsBase::CameraInfo(camera_info);
});

pimpl_->server.bind("simSetCameraOrientation", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Quaternionr& orientation,
pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose,
const std::string& vehicle_name) -> void {
getVehicleSimApi(vehicle_name)->setCameraOrientation(camera_name, orientation.to());
getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to());
});

pimpl_->server.bind("simSetCameraFov", [&](const std::string& camera_name, float fov_degrees,
Expand Down
8 changes: 4 additions & 4 deletions PythonClient/airsim/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -417,17 +417,17 @@ def simGetCameraInfo(self, camera_name, vehicle_name = ''):
# TODO: below str() conversion is only needed for legacy reason and should be removed in future
return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name))

def simSetCameraOrientation(self, camera_name, orientation, vehicle_name = ''):
def simSetCameraPose(self, camera_name, pose, vehicle_name = ''):
"""
- Control the orientation of a selected camera
- Control the pose of a selected camera
Args:
camera_name (str): Name of the camera to be controlled
orientation (Quaternionr): Quaternion representing the desired orientation of the camera
pose (Pose): Pose representing the desired position and 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)
self.client.call('simSetCameraPose', str(camera_name), pose, vehicle_name)

def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = ''):
"""
Expand Down
7 changes: 4 additions & 3 deletions PythonClient/computer_vision/cv_mode.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,9 @@
client = airsim.VehicleClient()
client.confirmConnection()

airsim.wait_key('Press any key to set camera-0 gimble to 15-degree pitch')
client.simSetCameraOrientation("0", airsim.to_quaternion(0.261799, 0, 0)); #radians
airsim.wait_key('Press any key to set camera-0 gimbal to 15-degree pitch')
camera_pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0.261799, 0, 0)) #radians
client.simSetCameraPose("0", camera_pose)

airsim.wait_key('Press any key to get camera parameters')
for camera_name in range(5):
Expand Down Expand Up @@ -48,4 +49,4 @@
time.sleep(3)

# currently reset() doesn't work in CV mode. Below is the workaround
client.simSetPose(airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0, 0, 0)), True)
client.simSetPose(airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0, 0, 0)), True)
6 changes: 4 additions & 2 deletions PythonClient/multirotor/gimbal.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@
for i in range(5):
client.moveToPositionAsync(float(-50.00), float( 50.26), float( -20.58), float( 3.5))
time.sleep(6)
client.simSetCameraOrientation("0", airsim.to_quaternion(0.5, 0.5, 0.1))
camera_pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0.5, 0.5, 0.1))
client.simSetCameraPose("0", camera_pose)
client.moveToPositionAsync(float(50.00), float( -50.26), float( -10.58), float( 3.5))
time.sleep(6)
client.simSetCameraOrientation("0", airsim.to_quaternion(-0.5, -0.5, -0.1))
camera_pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(-0.5, -0.5, -0.1))
client.simSetCameraPose("0", camera_pose)
6 changes: 3 additions & 3 deletions Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ bool(*SetEnableApi)(bool enableApi, const char* vehicleName);
bool(*SetCarApiControls)(msr::airlib::CarApiBase::CarControls controls, const char* vehicleName);
AirSimCarState(*GetCarState)(const char* vehicleName);
AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehicleName);
bool(*SetCameraOrientation)(const char* cameraName, AirSimQuaternion orientation, const char* vehicleName);
bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName);
bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName);
bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex);
int(*GetSegmentationObjectId)(const char* meshName);
Expand All @@ -33,7 +33,7 @@ void InitVehicleManager(
bool(*setCarApiControls)(msr::airlib::CarApiBase::CarControls controls, const char* vehicleName),
AirSimCarState(*getCarState)(const char* vehicleName),
AirSimCameraInfo(*getCameraInfo)(const char* cameraName, const char* vehicleName),
bool(*setCameraOrientation)(const char* cameraName, AirSimQuaternion orientation, const char* vehicleName),
bool(*setCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName),
bool(*setCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName),
bool(*setSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex),
int(*getSegmentationObjectId)(const char* meshName),
Expand All @@ -55,7 +55,7 @@ void InitVehicleManager(
SetCarApiControls = setCarApiControls;
GetCarState = getCarState;
GetCameraInfo = getCameraInfo;
SetCameraOrientation = setCameraOrientation;
SetCameraPose = setCameraPose;
SetCameraFoV = setCameraFoV;
SetSegmentationObjectId = setSegmentationObjectId;
GetSegmentationObjectId = getSegmentationObjectId;
Expand Down
4 changes: 2 additions & 2 deletions Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ extern bool(*SetEnableApi)(bool enableApi, const char* vehicleName);
extern bool(*SetCarApiControls)(msr::airlib::CarApiBase::CarControls controls, const char* vehicleName);
extern AirSimCarState(*GetCarState)(const char* vehicleName);
extern AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehicleName);
extern bool(*SetCameraOrientation)(const char* cameraName, AirSimQuaternion orientation, const char* vehicleName);
extern bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName);
extern bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName);
extern bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex);
extern int(*GetSegmentationObjectId)(const char* meshName);
Expand All @@ -49,7 +49,7 @@ extern "C" EXPORT void InitVehicleManager(
bool(*setCarApiControls)(msr::airlib::CarApiBase::CarControls controls, const char* vehicleName),
AirSimCarState(*getCarState)(const char* vehicleName),
AirSimCameraInfo(*getCameraInfo)(const char* cameraName, const char* vehicleName),
bool(*setCameraOrientation)(const char* cameraName, AirSimQuaternion orientation, const char* vehicleName),
bool(*setCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName),
bool(*setCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName),
bool(*setSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex),
int(*getSegmentationObjectId)(const char* meshName),
Expand Down
10 changes: 2 additions & 8 deletions Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -210,15 +210,9 @@ msr::airlib::CameraInfo PawnSimApi::getCameraInfo(const std::string& camera_name
return camera_info;
}

void PawnSimApi::setCameraOrientation(const std::string& camera_name, const msr::airlib::Quaternionr& orientation)
void PawnSimApi::setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose)
{
AirSimQuaternion airSimOrientation;
airSimOrientation.x = orientation.x();
airSimOrientation.y = orientation.y();
airSimOrientation.z = orientation.z();
airSimOrientation.w = orientation.w();

SetCameraOrientation(camera_name.c_str(), airSimOrientation, params_.vehicle_name.c_str());
SetCameraPose(camera_name.c_str(), UnityUtilities::Convert_to_AirSimPose(pose), params_.vehicle_name.c_str());
}

void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees)
Expand Down
2 changes: 1 addition & 1 deletion Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase
virtual Pose getPose() const override;
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 setCameraPose(const std::string& camera_name, const Pose& pose) override;
virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override;
virtual CollisionInfo getCollisionInfo() const override;
virtual int getRemoteControlID() const override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ public class DataCaptureScript : MonoBehaviour {
private Texture2D screenShot;
private Rect captureRect;
private AirSimPose currentPose;
private Quaternion poseFromAirLib;
private Pose poseFromAirLib;

private bool isCapturing;
private bool isPoseOverride;
Expand All @@ -40,7 +40,8 @@ private void FixedUpdate() {
DataManager.SetToAirSim(transform.rotation, ref currentPose.orientation);

if (isPoseOverride) {
transform.rotation = poseFromAirLib;
transform.position = poseFromAirLib.position;
transform.rotation = poseFromAirLib.rotation;
isPoseOverride = false;
}
}
Expand Down Expand Up @@ -89,8 +90,9 @@ public AirSimPose GetPose() {
return currentPose;
}

public void SetOrientation(AirSimQuaternion orientation) {
DataManager.SetToUnity(orientation, ref poseFromAirLib);
public void SetPose(AirSimPose pose) {
DataManager.SetToUnity(pose.position, ref poseFromAirLib.position);
DataManager.SetToUnity(pose.orientation, ref poseFromAirLib.rotation);
isPoseOverride = true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ public static class PInvokeWrapper {
[DllImport(DLL_NAME)]
public static extern void InitVehicleManager(IntPtr SetPose, IntPtr GetPose, IntPtr GetCollisionInfo, IntPtr GetRCData,
IntPtr GetSimImages, IntPtr SetRotorSpeed, IntPtr SetEnableApi, IntPtr SetCarApiControls, IntPtr GetCarState,
IntPtr GetCameraInfo, IntPtr SetCameraOrientation, IntPtr SetCameraFoV, IntPtr SetSegmentationObjectid, IntPtr GetSegmentationObjectId,
IntPtr GetCameraInfo, IntPtr SetCameraPose, IntPtr SetCameraFoV, IntPtr SetSegmentationObjectid, IntPtr GetSegmentationObjectId,
IntPtr PrintLogMessage, IntPtr GetTransformFromUnity, IntPtr Reset, IntPtr GetVelocity, IntPtr GetRayCastHit, IntPtr Pause);

[DllImport(DLL_NAME)]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public interface IVehicleInterface {

CameraInfo GetCameraInfo(string cameraName);

bool SetCameraOrientation(string cameraName, AirSimQuaternion orientation);
bool SetCameraPose(string cameraName, AirSimPose pose);

bool SetCameraFoV(string cameraName, float fov_degrees);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -264,10 +264,10 @@ public CameraInfo GetCameraInfo(string cameraName) {
return info;
}

public bool SetCameraOrientation(string cameraName, AirSimQuaternion orientation) {
public bool SetCameraPose(string cameraName, AirSimPose pose) {
foreach (DataCaptureScript capture in captureCameras) {
if (capture.GetCameraName() == cameraName) {
capture.SetOrientation(orientation);
capture.SetPose(pose);
return true;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ private static void InitDelegators() {
Marshal.GetFunctionPointerForDelegate(new Func<CarControls, string, bool>(SetCarApiControls)),
Marshal.GetFunctionPointerForDelegate(new Func<string, CarState>(GetCarState)),
Marshal.GetFunctionPointerForDelegate(new Func<string, string, CameraInfo>(GetCameraInfo)),
Marshal.GetFunctionPointerForDelegate(new Func<string, AirSimQuaternion, string, bool>(SetCameraOrientation)),
Marshal.GetFunctionPointerForDelegate(new Func<string, AirSimPose, string, bool>(SetCameraPose)),
Marshal.GetFunctionPointerForDelegate(new Func<string, float, string, bool>(SetCameraFoV)),
Marshal.GetFunctionPointerForDelegate(new Func<string, int, bool, bool>(SetSegmentationObjectId)),
Marshal.GetFunctionPointerForDelegate(new Func<string, int>(GetSegmentationObjectId)),
Expand Down Expand Up @@ -184,9 +184,9 @@ private static CameraInfo GetCameraInfo(string cameraName, string vehicleName) {
return vehicle.VehicleInterface.GetCameraInfo(cameraName);
}

private static bool SetCameraOrientation(string cameraName, AirSimQuaternion orientation, string vehicleName) {
private static bool SetCameraPose(string cameraName, AirSimPose pose, string vehicleName) {
var vehicle = Vehicles.Find(element => element.vehicleName == vehicleName);
return vehicle.VehicleInterface.SetCameraOrientation(cameraName, orientation);
return vehicle.VehicleInterface.SetCameraPose(cameraName, pose);
}

private static bool SetCameraFoV(string cameraName, float fov_degrees, string vehicleName) {
Expand Down
8 changes: 8 additions & 0 deletions Unreal/Plugins/AirSim/Source/NedTransform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,14 @@ FVector NedTransform::fromLocalNed(const NedTransform::Vector3r& position) const
{
return NedTransform::toFVector(position, world_to_meters_, true) + local_ned_offset_;
}
FVector NedTransform::fromRelativeNed(const NedTransform::Vector3r& position) const
{
return NedTransform::toFVector(position, world_to_meters_, true);
}
FTransform NedTransform::fromRelativeNed(const Pose& pose) const
{
return FTransform(fromNed(pose.orientation), fromRelativeNed(pose.position));
}
FVector NedTransform::fromGlobalNed(const NedTransform::Vector3r& position) const
{
return NedTransform::toFVector(position, world_to_meters_, true) + global_transform_.GetLocation();
Expand Down
2 changes: 2 additions & 0 deletions Unreal/Plugins/AirSim/Source/NedTransform.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ class AIRSIM_API NedTransform
FVector fromGlobalNed(const Vector3r& position) const;
FQuat fromNed(const Quaternionr& q) const;
float fromNed(float length) const;
FVector fromRelativeNed(const Vector3r& position) const;
FTransform fromRelativeNed(const Pose& pose) const;
FTransform fromLocalNed(const Pose& pose) const;
FTransform fromGlobalNed(const Pose& pose) const;

Expand Down
6 changes: 5 additions & 1 deletion Unreal/Plugins/AirSim/Source/PIPCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,8 +244,12 @@ void APIPCamera::setCameraTypeEnabled(ImageType type, bool enabled)
enableCaptureComponent(type, enabled);
}

void APIPCamera::setCameraOrientation(const FRotator& rotator)
void APIPCamera::setCameraPose(const FTransform& pose)
{
FVector position = pose.GetLocation();
this->SetActorRelativeLocation(pose.GetLocation());

FRotator rotator = pose.GetRotation().Rotator();
if (gimbal_stabilization_ > 0) {
gimbald_rotator_.Pitch = rotator.Pitch;
gimbald_rotator_.Roll = rotator.Roll;
Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/PIPCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class AIRSIM_API APIPCamera : public ACameraActor
void setCameraTypeEnabled(ImageType type, bool enabled);
bool getCameraTypeEnabled(ImageType type) const;
void setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform);
void setCameraOrientation(const FRotator& rotator);
void setCameraPose(const FTransform& pose);
void setCameraFoV(float fov_degrees);

msr::airlib::ProjectionMatrix getProjectionMatrix(const APIPCamera::ImageType image_type) const;
Expand Down
8 changes: 4 additions & 4 deletions Unreal/Plugins/AirSim/Source/PawnSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -409,12 +409,12 @@ msr::airlib::CameraInfo PawnSimApi::getCameraInfo(const std::string& camera_name
return camera_info;
}

void PawnSimApi::setCameraOrientation(const std::string& camera_name, const msr::airlib::Quaternionr& orientation)
void PawnSimApi::setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose)
{
UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, orientation]() {
UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, pose]() {
APIPCamera* camera = getCamera(camera_name);
FQuat quat = ned_transform_.fromNed(orientation);
camera->setCameraOrientation(quat.Rotator());
FTransform pose_unreal = ned_transform_.fromRelativeNed(pose);
camera->setCameraPose(pose_unreal);
}, true);
}

Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/PawnSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase {
virtual Pose getPose() const override;
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 setCameraPose(const std::string& camera_name, const Pose& pose) override;
virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override;
virtual CollisionInfo getCollisionInfo() const override;
virtual int getRemoteControlID() const override;
Expand Down
Loading

0 comments on commit 040a08a

Please sign in to comment.