зеркало из https://github.com/microsoft/AirSim.git
Plugin refactoring to sync with AirLib (Part 2)
This commit is contained in:
Родитель
78983c7d12
Коммит
a6f365f517
|
@ -50,6 +50,7 @@
|
||||||
<ClInclude Include="include\common\common_utils\ProsumerQueue.hpp" />
|
<ClInclude Include="include\common\common_utils\ProsumerQueue.hpp" />
|
||||||
<ClInclude Include="include\common\common_utils\RandomGenerator.hpp" />
|
<ClInclude Include="include\common\common_utils\RandomGenerator.hpp" />
|
||||||
<ClInclude Include="include\common\common_utils\ScheduledExecutor.hpp" />
|
<ClInclude Include="include\common\common_utils\ScheduledExecutor.hpp" />
|
||||||
|
<ClInclude Include="include\common\common_utils\Signal.hpp" />
|
||||||
<ClInclude Include="include\common\common_utils\sincos.hpp" />
|
<ClInclude Include="include\common\common_utils\sincos.hpp" />
|
||||||
<ClInclude Include="include\common\common_utils\StrictMode.hpp" />
|
<ClInclude Include="include\common\common_utils\StrictMode.hpp" />
|
||||||
<ClInclude Include="include\common\common_utils\Timer.hpp" />
|
<ClInclude Include="include\common\common_utils\Timer.hpp" />
|
||||||
|
|
|
@ -429,6 +429,9 @@
|
||||||
<ClInclude Include="include\api\ApiProvider.hpp">
|
<ClInclude Include="include\api\ApiProvider.hpp">
|
||||||
<Filter>Header Files</Filter>
|
<Filter>Header Files</Filter>
|
||||||
</ClInclude>
|
</ClInclude>
|
||||||
|
<ClInclude Include="include\common\common_utils\Signal.hpp">
|
||||||
|
<Filter>Header Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
<ClCompile Include="src\safety\ObstacleMap.cpp">
|
<ClCompile Include="src\safety\ObstacleMap.cpp">
|
||||||
|
|
|
@ -53,11 +53,23 @@ public:
|
||||||
{
|
{
|
||||||
return vehicle_apis_;
|
return vehicle_apis_;
|
||||||
}
|
}
|
||||||
const std::map<std::string, VehicleSimApiBase*>& getVehicleSimApis()
|
const std::map<std::string, VehicleSimApiBase*>& geVehicleSimApis()
|
||||||
{
|
{
|
||||||
return vehicle_sim_apis_;
|
return vehicle_sim_apis_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool hasDefaultVehicle() const
|
||||||
|
{
|
||||||
|
return Utils::findOrDefault<std::string, VehicleApiBase*>(vehicle_apis_, "") == nullptr &&
|
||||||
|
Utils::findOrDefault<std::string, VehicleSimApiBase*>(vehicle_sim_apis_, "") == nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
void makeDefaultVehicle(const std::string& vehicle_name)
|
||||||
|
{
|
||||||
|
vehicle_apis_[""] = vehicle_apis_[vehicle_name];
|
||||||
|
vehicle_sim_apis_[""] = vehicle_sim_apis_[vehicle_name];
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
WorldSimApiBase* world_sim_api_;
|
WorldSimApiBase* world_sim_api_;
|
||||||
|
|
||||||
|
|
|
@ -264,19 +264,19 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
struct ImageRequest {
|
struct ImageRequest {
|
||||||
uint8_t camera_id;
|
std::string camera_name;
|
||||||
msr::airlib::ImageCaptureBase::ImageType image_type;
|
msr::airlib::ImageCaptureBase::ImageType image_type;
|
||||||
bool pixels_as_float;
|
bool pixels_as_float;
|
||||||
bool compress;
|
bool compress;
|
||||||
|
|
||||||
MSGPACK_DEFINE_MAP(camera_id, image_type, pixels_as_float, compress);
|
MSGPACK_DEFINE_MAP(camera_name, image_type, pixels_as_float, compress);
|
||||||
|
|
||||||
ImageRequest()
|
ImageRequest()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
ImageRequest(const msr::airlib::ImageCaptureBase::ImageRequest& s)
|
ImageRequest(const msr::airlib::ImageCaptureBase::ImageRequest& s)
|
||||||
{
|
{
|
||||||
camera_id = s.camera_id;
|
camera_name = s.camera_name;
|
||||||
image_type = s.image_type;
|
image_type = s.image_type;
|
||||||
pixels_as_float = s.pixels_as_float;
|
pixels_as_float = s.pixels_as_float;
|
||||||
compress = s.compress;
|
compress = s.compress;
|
||||||
|
@ -285,7 +285,7 @@ public:
|
||||||
msr::airlib::ImageCaptureBase::ImageRequest to() const
|
msr::airlib::ImageCaptureBase::ImageRequest to() const
|
||||||
{
|
{
|
||||||
msr::airlib::ImageCaptureBase::ImageRequest d;
|
msr::airlib::ImageCaptureBase::ImageRequest d;
|
||||||
d.camera_id = camera_id;
|
d.camera_name = camera_name;
|
||||||
d.image_type = image_type;
|
d.image_type = image_type;
|
||||||
d.pixels_as_float = pixels_as_float;
|
d.pixels_as_float = pixels_as_float;
|
||||||
d.compress = compress;
|
d.compress = compress;
|
||||||
|
|
|
@ -45,7 +45,7 @@ public:
|
||||||
Pose simGetObjectPose(const std::string& object_name) const;
|
Pose simGetObjectPose(const std::string& object_name) const;
|
||||||
|
|
||||||
vector<ImageCaptureBase::ImageResponse> simGetImages(vector<ImageCaptureBase::ImageRequest> request);
|
vector<ImageCaptureBase::ImageResponse> simGetImages(vector<ImageCaptureBase::ImageRequest> request);
|
||||||
vector<uint8_t> simGetImage(int camera_id, ImageCaptureBase::ImageType type);
|
vector<uint8_t> simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type);
|
||||||
|
|
||||||
CollisionInfo simGetCollisionInfo() const;
|
CollisionInfo simGetCollisionInfo() const;
|
||||||
|
|
||||||
|
@ -53,8 +53,8 @@ public:
|
||||||
int simGetSegmentationObjectID(const std::string& mesh_name) const;
|
int simGetSegmentationObjectID(const std::string& mesh_name) const;
|
||||||
void simPrintLogMessage(const std::string& message, std::string message_param = "", unsigned char severity = 0);
|
void simPrintLogMessage(const std::string& message, std::string message_param = "", unsigned char severity = 0);
|
||||||
|
|
||||||
CameraInfo simGetCameraInfo(int camera_id) const;
|
CameraInfo simGetCameraInfo(const std::string& camera_name) const;
|
||||||
void simSetCameraOrientation(int camera_id, const Quaternionr& orientation);
|
void simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation);
|
||||||
|
|
||||||
//task management APIs
|
//task management APIs
|
||||||
void cancelLastTask();
|
void cancelLastTask();
|
||||||
|
|
|
@ -50,10 +50,13 @@ public:
|
||||||
virtual RCData getRCData() const = 0; //get reading from RC from simulator
|
virtual RCData getRCData() const = 0; //get reading from RC from simulator
|
||||||
virtual std::string getVehicleName() const = 0;
|
virtual std::string getVehicleName() const = 0;
|
||||||
virtual std::string getLogLine() const = 0;
|
virtual std::string getLogLine() const = 0;
|
||||||
|
virtual void setLogLine(std::string line) = 0;
|
||||||
|
virtual void toggleTrace() = 0;
|
||||||
|
|
||||||
const AirSimSettings::VehicleSetting& getVehicleSetting() const
|
//use pointer here because of derived classes for VehicleSetting
|
||||||
|
const AirSimSettings::VehicleSetting* getVehicleSetting() const
|
||||||
{
|
{
|
||||||
return *(AirSimSettings::singleton().getVehicleSetting(getVehicleName()));
|
return AirSimSettings::singleton().getVehicleSetting(getVehicleName());
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -31,10 +31,10 @@ public: //types
|
||||||
int window_index;
|
int window_index;
|
||||||
ImageType image_type;
|
ImageType image_type;
|
||||||
bool visible;
|
bool visible;
|
||||||
int camera_id;
|
std::string camera_name;
|
||||||
|
|
||||||
SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, bool visible_val = false, int camera_id_val = 0)
|
SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, bool visible_val = false, const std::string& camera_name_val = 0)
|
||||||
: window_index(window_index_val), image_type(image_type_val), visible(visible_val), camera_id(camera_id_val)
|
: window_index(window_index_val), image_type(image_type_val), visible(visible_val), camera_name(camera_name_val)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -848,7 +848,7 @@ private:
|
||||||
subwindow_setting.image_type = Utils::toEnum<ImageType>(
|
subwindow_setting.image_type = Utils::toEnum<ImageType>(
|
||||||
json_settings_child.getInt("ImageType", 0));
|
json_settings_child.getInt("ImageType", 0));
|
||||||
subwindow_setting.visible = json_settings_child.getBool("Visible", false);
|
subwindow_setting.visible = json_settings_child.getBool("Visible", false);
|
||||||
subwindow_setting.camera_id = json_settings_child.getInt("CameraID", 0);
|
subwindow_setting.camera_name = json_settings_child.getString("CameraName", "");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -13,7 +13,7 @@ namespace msr { namespace airlib {
|
||||||
class ImageCaptureBase
|
class ImageCaptureBase
|
||||||
{
|
{
|
||||||
public: //types
|
public: //types
|
||||||
enum class ImageType : uint { //this indexes to array
|
enum class ImageType : int { //this indexes to array, -1 is special to indicate main camera
|
||||||
Scene = 0,
|
Scene = 0,
|
||||||
DepthPlanner,
|
DepthPlanner,
|
||||||
DepthPerspective,
|
DepthPerspective,
|
||||||
|
|
|
@ -0,0 +1,101 @@
|
||||||
|
#ifndef common_utils_Signal_hpp
|
||||||
|
#define common_utils_Signal_hpp
|
||||||
|
|
||||||
|
#include <functional>
|
||||||
|
#include <map>
|
||||||
|
|
||||||
|
// A signal object may call multiple slots with the
|
||||||
|
// same signature. You can connect functions to the signal
|
||||||
|
// which will be called when the emit() method on the
|
||||||
|
// signal object is invoked. Any argument passed to emit()
|
||||||
|
// will be passed to the given functions.
|
||||||
|
|
||||||
|
/*
|
||||||
|
//USAGE:
|
||||||
|
|
||||||
|
#include "Signal.hpp"
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
|
||||||
|
// create new signal
|
||||||
|
Signal<std::string, int> signal;
|
||||||
|
|
||||||
|
// attach a slot
|
||||||
|
signal.connect([](std::string arg1, int arg2) {
|
||||||
|
std::cout << arg1 << " " << arg2 << std::endl;
|
||||||
|
});
|
||||||
|
|
||||||
|
signal.emit("The answer:", 42);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
namespace common_utils {
|
||||||
|
|
||||||
|
|
||||||
|
template <typename... Args>
|
||||||
|
class Signal {
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
Signal() : current_id_(0) {}
|
||||||
|
|
||||||
|
// copy creates new signal
|
||||||
|
Signal(Signal const& other) : current_id_(0) {}
|
||||||
|
|
||||||
|
// connects a member function to this Signal
|
||||||
|
template <typename T>
|
||||||
|
int connect_member(T *inst, void (T::*func)(Args...)) {
|
||||||
|
return connect([=](Args... args) {
|
||||||
|
(inst->*func)(args...);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
// connects a const member function to this Signal
|
||||||
|
template <typename T>
|
||||||
|
int connect_member(T *inst, void (T::*func)(Args...) const) {
|
||||||
|
return connect([=](Args... args) {
|
||||||
|
(inst->*func)(args...);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
// connects a std::function to the signal. The returned
|
||||||
|
// value can be used to disconnect the function again
|
||||||
|
int connect(std::function<void(Args...)> const& slot) const {
|
||||||
|
slots_.insert(std::make_pair(++current_id_, slot));
|
||||||
|
return current_id_;
|
||||||
|
}
|
||||||
|
|
||||||
|
// disconnects a previously connected function
|
||||||
|
void disconnect(int id) const {
|
||||||
|
slots_.erase(id);
|
||||||
|
}
|
||||||
|
|
||||||
|
// disconnects all previously connected functions
|
||||||
|
void disconnect_all() const {
|
||||||
|
slots_.clear();
|
||||||
|
}
|
||||||
|
|
||||||
|
// calls all connected functions
|
||||||
|
void emit(Args... p) {
|
||||||
|
for (auto it : slots_) {
|
||||||
|
it.second(p...);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// assignment creates new Signal
|
||||||
|
Signal& operator=(Signal const& other) {
|
||||||
|
disconnect_all();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
mutable std::map<int, std::function<void(Args...)>> slots_;
|
||||||
|
mutable int current_id_;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* common_utils_Signal_hpp */
|
|
@ -127,13 +127,21 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
template <template<class, class, class...> class TContainer, typename TKey, typename TVal, typename... Args>
|
template <template<class, class, class...> class TContainer, typename TKey, typename TVal, typename... Args>
|
||||||
static TVal findOrDefault(const TContainer<TKey, TVal, Args...>& m, TKey const& key, const TVal & default_val)
|
static TVal findOrDefault(const TContainer<TKey, TVal, Args...>& m, TKey const& key, const TVal& default_val)
|
||||||
{
|
{
|
||||||
typename TContainer<TKey, TVal, Args...>::const_iterator it = m.find(key);
|
typename TContainer<TKey, TVal, Args...>::const_iterator it = m.find(key);
|
||||||
if (it == m.end())
|
if (it == m.end())
|
||||||
return default_val;
|
return default_val;
|
||||||
return it->second;
|
return it->second;
|
||||||
}
|
}
|
||||||
|
template <typename TKey, typename TVal>
|
||||||
|
static TVal findOrDefault(const std::map<TKey, TVal>& m, TKey const& key, const TVal& default_val = TVal())
|
||||||
|
{
|
||||||
|
typename TContainer<TKey, TVal>::const_iterator it = m.find(key);
|
||||||
|
if (it == m.end())
|
||||||
|
return default_val;
|
||||||
|
return it->second;
|
||||||
|
}
|
||||||
|
|
||||||
static Logger* getSetLogger(Logger* logger = nullptr)
|
static Logger* getSetLogger(Logger* logger = nullptr)
|
||||||
{
|
{
|
||||||
|
|
|
@ -28,7 +28,7 @@ public:
|
||||||
SimpleFlightApi(const MultiRotorParams* vehicle_params, const AirSimSettings::VehicleSetting* vehicle_setting)
|
SimpleFlightApi(const MultiRotorParams* vehicle_params, const AirSimSettings::VehicleSetting* vehicle_setting)
|
||||||
: vehicle_params_(vehicle_params)
|
: vehicle_params_(vehicle_params)
|
||||||
{
|
{
|
||||||
readSettings(vehicle_setting);
|
readSettings(*vehicle_setting);
|
||||||
|
|
||||||
//TODO: set below properly for better high speed safety
|
//TODO: set below properly for better high speed safety
|
||||||
safety_params_.vel_to_breaking_dist = safety_params_.min_breaking_dist = 0;
|
safety_params_.vel_to_breaking_dist = safety_params_.min_breaking_dist = 0;
|
||||||
|
@ -127,6 +127,8 @@ public: //MultirotorApiBase implementation
|
||||||
else { //else we don't have RC data
|
else { //else we don't have RC data
|
||||||
board_->setIsRcConnected(false);
|
board_->setIsRcConnected(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
@ -280,14 +282,14 @@ private:
|
||||||
return static_cast<uint16_t>(1000.0f * switchVal / maxSwitchVal + 1000.0f);
|
return static_cast<uint16_t>(1000.0f * switchVal / maxSwitchVal + 1000.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
void readSettings(const AirSimSettings::VehicleSetting* vehicle_setting)
|
void readSettings(const AirSimSettings::VehicleSetting& vehicle_setting)
|
||||||
{
|
{
|
||||||
params_.default_vehicle_state = simple_flight::VehicleState::fromString(
|
params_.default_vehicle_state = simple_flight::VehicleState::fromString(
|
||||||
vehicle_setting->default_vehicle_state == "" ? "Armed" : vehicle_setting->default_vehicle_state);
|
vehicle_setting.default_vehicle_state == "" ? "Armed" : vehicle_setting.default_vehicle_state);
|
||||||
|
|
||||||
remote_control_id_ = vehicle_setting->rc.remote_control_id;
|
remote_control_id_ = vehicle_setting.rc.remote_control_id;
|
||||||
params_.rc.allow_api_when_disconnected = vehicle_setting->rc.allow_api_when_disconnected;
|
params_.rc.allow_api_when_disconnected = vehicle_setting.rc.allow_api_when_disconnected;
|
||||||
params_.rc.allow_api_always = vehicle_setting->allow_api_always;
|
params_.rc.allow_api_always = vehicle_setting.allow_api_always;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
|
@ -68,7 +68,7 @@ protected:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
vector<unique_ptr<SensorBase>> sensor_storage_;
|
vector<unique_ptr<SensorBase>> sensor_storage_;
|
||||||
const AirSimSettings::VehicleSetting* vehicle_setting_;
|
const AirSimSettings::VehicleSetting* vehicle_setting_; //store as pointer because of derived classes
|
||||||
std::shared_ptr<const SensorFactory> sensor_factory_;
|
std::shared_ptr<const SensorFactory> sensor_factory_;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -179,9 +179,9 @@ vector<ImageCaptureBase::ImageResponse> RpcLibClientBase::simGetImages(vector<Im
|
||||||
|
|
||||||
return RpcLibAdapatorsBase::ImageResponse::to(response_adaptor);
|
return RpcLibAdapatorsBase::ImageResponse::to(response_adaptor);
|
||||||
}
|
}
|
||||||
vector<uint8_t> RpcLibClientBase::simGetImage(int camera_id, ImageCaptureBase::ImageType type)
|
vector<uint8_t> RpcLibClientBase::simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type)
|
||||||
{
|
{
|
||||||
vector<uint8_t> result = pimpl_->client.call("simGetImage", camera_id, type).as<vector<uint8_t>>();
|
vector<uint8_t> result = pimpl_->client.call("simGetImage", camera_name, type).as<vector<uint8_t>>();
|
||||||
if (result.size() == 1) {
|
if (result.size() == 1) {
|
||||||
// rpclib has a bug with serializing empty vectors, so we return a 1 byte vector instead.
|
// rpclib has a bug with serializing empty vectors, so we return a 1 byte vector instead.
|
||||||
result.clear();
|
result.clear();
|
||||||
|
@ -214,13 +214,13 @@ msr::airlib::Pose RpcLibClientBase::simGetObjectPose(const std::string& object_n
|
||||||
return pimpl_->client.call("simGetObjectPose", object_name).as<RpcLibAdapatorsBase::Pose>().to();
|
return pimpl_->client.call("simGetObjectPose", object_name).as<RpcLibAdapatorsBase::Pose>().to();
|
||||||
}
|
}
|
||||||
|
|
||||||
CameraInfo RpcLibClientBase::simGetCameraInfo(int camera_id) const
|
CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name) const
|
||||||
{
|
{
|
||||||
return pimpl_->client.call("simGetCameraInfo", camera_id).as<RpcLibAdapatorsBase::CameraInfo>().to();
|
return pimpl_->client.call("simGetCameraInfo", camera_name).as<RpcLibAdapatorsBase::CameraInfo>().to();
|
||||||
}
|
}
|
||||||
void RpcLibClientBase::simSetCameraOrientation(int camera_id, const Quaternionr& orientation)
|
void RpcLibClientBase::simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation)
|
||||||
{
|
{
|
||||||
pimpl_->client.call("simSetCameraOrientation", camera_id, RpcLibAdapatorsBase::Quaternionr(orientation));
|
pimpl_->client.call("simSetCameraOrientation", camera_name, RpcLibAdapatorsBase::Quaternionr(orientation));
|
||||||
}
|
}
|
||||||
|
|
||||||
void RpcLibClientBase::cancelLastTask()
|
void RpcLibClientBase::cancelLastTask()
|
||||||
|
|
|
@ -81,8 +81,8 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
|
||||||
const auto& response = getVehicleSimApi()->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter));
|
const auto& response = getVehicleSimApi()->getImages(RpcLibAdapatorsBase::ImageRequest::to(request_adapter));
|
||||||
return RpcLibAdapatorsBase::ImageResponse::from(response);
|
return RpcLibAdapatorsBase::ImageResponse::from(response);
|
||||||
});
|
});
|
||||||
pimpl_->server.bind("simGetImage", [&](uint8_t camera_id, ImageCaptureBase::ImageType type) -> vector<uint8_t> {
|
pimpl_->server.bind("simGetImage", [&](const std::string& camera_name, ImageCaptureBase::ImageType type) -> vector<uint8_t> {
|
||||||
auto result = getVehicleSimApi()->getImage(camera_id, type);
|
auto result = getVehicleSimApi()->getImage(camera_name, type);
|
||||||
if (result.size() == 0) {
|
if (result.size() == 0) {
|
||||||
// rpclib has a bug with serializing empty vectors, so we return a 1 byte vector instead.
|
// rpclib has a bug with serializing empty vectors, so we return a 1 byte vector instead.
|
||||||
result.push_back(0);
|
result.push_back(0);
|
||||||
|
@ -125,13 +125,13 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
|
||||||
return RpcLibAdapatorsBase::GeoPoint(geo_point);
|
return RpcLibAdapatorsBase::GeoPoint(geo_point);
|
||||||
});
|
});
|
||||||
|
|
||||||
pimpl_->server.bind("simGetCameraInfo", [&](int camera_id) -> RpcLibAdapatorsBase::CameraInfo {
|
pimpl_->server.bind("simGetCameraInfo", [&](const std::string& camera_name) -> RpcLibAdapatorsBase::CameraInfo {
|
||||||
const auto& camera_info = getVehicleSimApi()->getCameraInfo(camera_id);
|
const auto& camera_info = getVehicleSimApi()->getCameraInfo(camera_name);
|
||||||
return RpcLibAdapatorsBase::CameraInfo(camera_info);
|
return RpcLibAdapatorsBase::CameraInfo(camera_info);
|
||||||
});
|
});
|
||||||
|
|
||||||
pimpl_->server.bind("simSetCameraOrientation", [&](int camera_id, const RpcLibAdapatorsBase::Quaternionr& orientation) -> void {
|
pimpl_->server.bind("simSetCameraOrientation", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Quaternionr& orientation) -> void {
|
||||||
getVehicleSimApi()->setCameraOrientation(camera_id, orientation.to());
|
getVehicleSimApi()->setCameraOrientation(camera_name, orientation.to());
|
||||||
});
|
});
|
||||||
|
|
||||||
pimpl_->server.bind("simGetCollisionInfo", [&]() -> RpcLibAdapatorsBase::CollisionInfo {
|
pimpl_->server.bind("simGetCollisionInfo", [&]() -> RpcLibAdapatorsBase::CollisionInfo {
|
||||||
|
|
|
@ -28,9 +28,7 @@ public:
|
||||||
std::make_shared<SensorFactory>());
|
std::make_shared<SensorFactory>());
|
||||||
auto api = params->createMultirotorApi();
|
auto api = params->createMultirotorApi();
|
||||||
|
|
||||||
std::unique_ptr<Environment> environment;
|
MultiRotor vehicle(params.get(), api.get(), Pose());
|
||||||
MultiRotor vehicle(params.get(), api.get(), Pose(),
|
|
||||||
GeoPoint(), environment);
|
|
||||||
|
|
||||||
std::vector<UpdatableObject*> vehicles = { &vehicle };
|
std::vector<UpdatableObject*> vehicles = { &vehicle };
|
||||||
std::unique_ptr<PhysicsEngineBase> physics_engine(new FastPhysicsEngine());
|
std::unique_ptr<PhysicsEngineBase> physics_engine(new FastPhysicsEngine());
|
||||||
|
|
|
@ -81,7 +81,7 @@ int main(int argc, const char* argv[])
|
||||||
|
|
||||||
|
|
||||||
ApiProvider api_provider(nullptr);
|
ApiProvider api_provider(nullptr);
|
||||||
api_provider.insert_or_assign("", &api);
|
api_provider.insert_or_assign("", &api, nullptr);
|
||||||
msr::airlib::MultirotorRpcLibServer server(&api_provider, connection_info.local_host_ip);
|
msr::airlib::MultirotorRpcLibServer server(&api_provider, connection_info.local_host_ip);
|
||||||
|
|
||||||
//start server in async mode
|
//start server in async mode
|
||||||
|
|
|
@ -61,9 +61,9 @@ public:
|
||||||
auto start_nanos = clock->nowNanos();
|
auto start_nanos = clock->nowNanos();
|
||||||
|
|
||||||
std::vector<ImageRequest> request = {
|
std::vector<ImageRequest> request = {
|
||||||
ImageRequest(0, ImageType::Scene),
|
ImageRequest("0", ImageType::Scene),
|
||||||
ImageRequest(1, ImageType::Scene),
|
ImageRequest("1", ImageType::Scene),
|
||||||
ImageRequest(1, ImageType::DisparityNormalized, true)
|
ImageRequest("1", ImageType::DisparityNormalized, true)
|
||||||
};
|
};
|
||||||
const std::vector<ImageResponse>& response = client.simGetImages(request);
|
const std::vector<ImageResponse>& response = client.simGetImages(request);
|
||||||
if (response.size() != 3) {
|
if (response.size() != 3) {
|
||||||
|
|
|
@ -34,9 +34,9 @@ int main()
|
||||||
client.confirmConnection();
|
client.confirmConnection();
|
||||||
|
|
||||||
std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get();
|
std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get();
|
||||||
vector<ImageRequest> request = { ImageRequest(0, ImageType::Scene), ImageRequest(1, ImageType::DepthPlanner, true) };
|
vector<ImageRequest> request = { ImageRequest("0", ImageType::Scene), ImageRequest("1", ImageType::DepthPlanner, true) };
|
||||||
const vector<ImageResponse>& response = client.simGetImages(request);
|
const vector<ImageResponse>& response = client.simGetImages(request);
|
||||||
std::cout << "# of images recieved: " << response.size() << std::endl;
|
std::cout << "# of images received: " << response.size() << std::endl;
|
||||||
|
|
||||||
if (response.size() > 0) {
|
if (response.size() > 0) {
|
||||||
std::cout << "Enter path with ending separator to save images (leave empty for no save)" << std::endl;
|
std::cout << "Enter path with ending separator to save images (leave empty for no save)" << std::endl;
|
||||||
|
|
|
@ -30,9 +30,9 @@ int main()
|
||||||
client.confirmConnection();
|
client.confirmConnection();
|
||||||
|
|
||||||
std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get();
|
std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get();
|
||||||
vector<ImageRequest> request = { ImageRequest(0, ImageType::Scene), ImageRequest(1, ImageType::DepthPlanner, true) };
|
vector<ImageRequest> request = { ImageRequest("0", ImageType::Scene), ImageRequest("1", ImageType::DepthPlanner, true) };
|
||||||
const vector<ImageResponse>& response = client.simGetImages(request);
|
const vector<ImageResponse>& response = client.simGetImages(request);
|
||||||
std::cout << "# of images recieved: " << response.size() << std::endl;
|
std::cout << "# of images received: " << response.size() << std::endl;
|
||||||
|
|
||||||
if (response.size() > 0) {
|
if (response.size() > 0) {
|
||||||
std::cout << "Enter path with ending separator to save images (leave empty for no save)" << std::endl;
|
std::cout << "Enter path with ending separator to save images (leave empty for no save)" << std::endl;
|
||||||
|
|
|
@ -107,7 +107,7 @@ public:
|
||||||
void onHandbrakePressed();
|
void onHandbrakePressed();
|
||||||
/** Handle handbrake released */
|
/** Handle handbrake released */
|
||||||
void onHandbrakeReleased();
|
void onHandbrakeReleased();
|
||||||
/** Handle pressiong footbrake */
|
/** Handle processing footbrake */
|
||||||
void FootBrake(float Val);
|
void FootBrake(float Val);
|
||||||
/** Handle Reverse pressed */
|
/** Handle Reverse pressed */
|
||||||
void onReversePressed();
|
void onReversePressed();
|
||||||
|
@ -115,7 +115,7 @@ public:
|
||||||
void onReverseReleased();
|
void onReverseReleased();
|
||||||
/** Handle Handbrake pressed */
|
/** Handle Handbrake pressed */
|
||||||
|
|
||||||
/** Setup the strings used on the hud */
|
/** Setup the strings used on the HUD */
|
||||||
void updateInCarHUD();
|
void updateInCarHUD();
|
||||||
|
|
||||||
/** update the physics material used by the vehicle mesh */
|
/** update the physics material used by the vehicle mesh */
|
||||||
|
@ -137,7 +137,7 @@ private:
|
||||||
|
|
||||||
UClass* pip_camera_class_;
|
UClass* pip_camera_class_;
|
||||||
|
|
||||||
VehicleSimApiBase* vehicle_sim_api_;
|
msr::airlib::VehicleSimApiBase* vehicle_sim_api_;
|
||||||
msr::airlib::Kinematics::State kinematics_;
|
msr::airlib::Kinematics::State kinematics_;
|
||||||
|
|
||||||
CarPawnApi::CarControls keyboard_controls_;
|
CarPawnApi::CarControls keyboard_controls_;
|
||||||
|
|
|
@ -95,7 +95,7 @@ void ASimModeCar::setupClockSpeed()
|
||||||
UAirBlueprintLib::LogMessageString("Clock Speed: ", std::to_string(current_clockspeed_), LogDebugLevel::Informational);
|
UAirBlueprintLib::LogMessageString("Clock Speed: ", std::to_string(current_clockspeed_), LogDebugLevel::Informational);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ASimModeCar::setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles)
|
void ASimModeCar::setupVehiclesAndCamera(std::vector<TVehiclePawn*>& vehicles)
|
||||||
{
|
{
|
||||||
//get player controller
|
//get player controller
|
||||||
APlayerController* player_controller = this->GetWorld()->GetFirstPlayerController();
|
APlayerController* player_controller = this->GetWorld()->GetFirstPlayerController();
|
||||||
|
@ -204,7 +204,7 @@ int ASimModeCar::getRemoteControlID(const VehicleSimApi& pawn) const
|
||||||
return fpv_vehicle_sim_api_->getRemoteControlID();
|
return fpv_vehicle_sim_api_->getRemoteControlID();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ASimModeCar::createVehicles(std::vector<VehiclePtr>& vehicles)
|
void ASimModeCar::createVehicles(std::vector<TVehiclePawn*>& vehicles)
|
||||||
{
|
{
|
||||||
//find vehicles and cameras available in environment
|
//find vehicles and cameras available in environment
|
||||||
//if none available then we will create one
|
//if none available then we will create one
|
||||||
|
@ -247,7 +247,7 @@ void ASimModeCar::Tick(float DeltaSeconds)
|
||||||
|
|
||||||
void ASimModeCar::updateDebugReport()
|
void ASimModeCar::updateDebugReport()
|
||||||
{
|
{
|
||||||
for (VehiclePtr vehicle : vehicles_) {
|
for (TVehiclePawn* vehicle : vehicles_) {
|
||||||
VehicleSimApi* vehicle_sim_api = vehicle->getVehicleSimApi();
|
VehicleSimApi* vehicle_sim_api = vehicle->getVehicleSimApi();
|
||||||
msr::airlib::StateReporter& reporter = *debug_reporter_.getReporter();
|
msr::airlib::StateReporter& reporter = *debug_reporter_.getReporter();
|
||||||
std::string vehicle_name = fpv_vehicle_sim_api_->getVehicleSetting()->vehicle_name;
|
std::string vehicle_name = fpv_vehicle_sim_api_->getVehicleSetting()->vehicle_name;
|
||||||
|
|
|
@ -16,9 +16,6 @@ class AIRSIM_API ASimModeCar : public ASimModeBase
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
public:
|
public:
|
||||||
typedef ACarPawn* VehiclePtr;
|
|
||||||
typedef ACarPawn TVehiclePawn;
|
|
||||||
|
|
||||||
ASimModeCar();
|
ASimModeCar();
|
||||||
virtual void BeginPlay() override;
|
virtual void BeginPlay() override;
|
||||||
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
||||||
|
@ -31,29 +28,32 @@ public:
|
||||||
virtual void pause(bool is_paused) override;
|
virtual void pause(bool is_paused) override;
|
||||||
virtual void continueForTime(double seconds) override;
|
virtual void continueForTime(double seconds) override;
|
||||||
|
|
||||||
private:
|
|
||||||
void setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles);
|
|
||||||
void updateDebugReport();
|
|
||||||
int getRemoteControlID(const VehicleSimApi& pawn) const;
|
|
||||||
void initializePauseState();
|
|
||||||
|
|
||||||
protected:
|
|
||||||
virtual void setupClockSpeed() override;
|
|
||||||
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const override;
|
|
||||||
virtual void createVehicles(std::vector<VehiclePtr>& vehicles);
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
typedef msr::airlib::ClockFactory ClockFactory;
|
typedef msr::airlib::ClockFactory ClockFactory;
|
||||||
typedef common_utils::Utils Utils;
|
typedef common_utils::Utils Utils;
|
||||||
typedef msr::airlib::TTimePoint TTimePoint;
|
typedef msr::airlib::TTimePoint TTimePoint;
|
||||||
typedef msr::airlib::TTimeDelta TTimeDelta;
|
typedef msr::airlib::TTimeDelta TTimeDelta;
|
||||||
|
typedef ACarPawn TVehiclePawn;
|
||||||
|
|
||||||
|
private:
|
||||||
|
void setupVehiclesAndCamera(std::vector<TVehiclePawn*>& vehicles);
|
||||||
|
void updateDebugReport();
|
||||||
|
int getRemoteControlID(const VehicleSimApi& pawn) const;
|
||||||
|
void initializePauseState();
|
||||||
|
void createVehicles(std::vector<TVehiclePawn*>& vehicles);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void setupClockSpeed() override;
|
||||||
|
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const override;
|
||||||
|
|
||||||
|
private:
|
||||||
UClass* external_camera_class_;
|
UClass* external_camera_class_;
|
||||||
UClass* camera_director_class_;
|
UClass* camera_director_class_;
|
||||||
|
|
||||||
TArray<AActor*> spawned_actors_;
|
UPROPERTY()
|
||||||
std::vector<VehiclePtr> vehicles_;
|
TArray<AActor*> spawned_actors_; //keep refs alive from Unreal GC
|
||||||
VehicleSimApiBase* fpv_vehicle_sim_api_;
|
|
||||||
|
std::vector<TVehiclePawn*> vehicles_;
|
||||||
float follow_distance_;
|
float follow_distance_;
|
||||||
msr::airlib::StateReporterWrapper debug_reporter_;
|
msr::airlib::StateReporterWrapper debug_reporter_;
|
||||||
|
|
||||||
|
|
|
@ -1,33 +1,21 @@
|
||||||
#include "FlyingPawn.h"
|
#include "FlyingPawn.h"
|
||||||
#include "Components/StaticMeshComponent.h"
|
#include "Components/StaticMeshComponent.h"
|
||||||
#include "Engine/World.h"
|
|
||||||
#include "AirBlueprintLib.h"
|
#include "AirBlueprintLib.h"
|
||||||
#include "common/CommonStructs.hpp"
|
#include "common/CommonStructs.hpp"
|
||||||
#include "common/Common.hpp"
|
#include "common/Common.hpp"
|
||||||
#include "VehicleSimApi.h"
|
|
||||||
|
|
||||||
AFlyingPawn::AFlyingPawn()
|
|
||||||
{
|
|
||||||
static ConstructorHelpers::FClassFinder<APIPCamera> pip_camera_class(TEXT("Blueprint'/AirSim/Blueprints/BP_PIPCamera'"));
|
|
||||||
pip_camera_class_ = pip_camera_class.Succeeded() ? pip_camera_class.Class : nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
void AFlyingPawn::BeginPlay()
|
void AFlyingPawn::BeginPlay()
|
||||||
{
|
{
|
||||||
Super::BeginPlay();
|
Super::BeginPlay();
|
||||||
}
|
|
||||||
void AFlyingPawn::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
for (auto i = 0; i < rotor_count; ++i) {
|
||||||
{
|
rotating_movements_[i] = UAirBlueprintLib::GetActorComponent<URotatingMovementComponent>(this, TEXT("Rotation") + FString::FromInt(i));
|
||||||
vehicle_sim_api_.reset();
|
}
|
||||||
cameras_.clear();
|
|
||||||
Super::EndPlay(EndPlayReason);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AFlyingPawn::initializeForBeginPlay(const NedTransform& global_transform, const std::string& vehicle_name)
|
void AFlyingPawn::initializeForBeginPlay()
|
||||||
{
|
{
|
||||||
cameras_.clear();
|
|
||||||
vehicle_sim_api_.reset(new VehicleSimApi(this, &cameras_, global_transform, vehicle_name));
|
|
||||||
|
|
||||||
//get references of existing camera
|
//get references of existing camera
|
||||||
fpv_camera_front_right_ = Cast<APIPCamera>(
|
fpv_camera_front_right_ = Cast<APIPCamera>(
|
||||||
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("FrontRightCamera")))->GetChildActor());
|
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("FrontRightCamera")))->GetChildActor());
|
||||||
|
@ -39,46 +27,36 @@ void AFlyingPawn::initializeForBeginPlay(const NedTransform& global_transform, c
|
||||||
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("BackCenterCamera")))->GetChildActor());
|
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("BackCenterCamera")))->GetChildActor());
|
||||||
fpv_camera_bottom_center_ = Cast<APIPCamera>(
|
fpv_camera_bottom_center_ = Cast<APIPCamera>(
|
||||||
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("BottomCenterCamera")))->GetChildActor());
|
(UAirBlueprintLib::GetActorComponent<UChildActorComponent>(this, TEXT("BottomCenterCamera")))->GetChildActor());
|
||||||
|
}
|
||||||
|
|
||||||
cameras_["0"] = cameras_["front_center"] = fpv_camera_front_center_;
|
void AFlyingPawn::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||||
cameras_["1"] = cameras_["front_right"] = fpv_camera_front_right_;
|
{
|
||||||
cameras_["2"] = cameras_["front_left"] = fpv_camera_front_left_;
|
fpv_camera_front_right_ = nullptr;
|
||||||
cameras_["3"] = cameras_["bottom_center"] = fpv_camera_bottom_center_;
|
fpv_camera_front_left_ = nullptr;
|
||||||
cameras_["4"] = cameras_["back_center"] = fpv_camera_back_center_;
|
fpv_camera_front_center_ = nullptr;
|
||||||
|
fpv_camera_back_center_ = nullptr;
|
||||||
|
fpv_camera_bottom_center_ = nullptr;
|
||||||
|
|
||||||
//UStaticMeshComponent* bodyMesh = UAirBlueprintLib::GetActorComponent<UStaticMeshComponent>(this, TEXT("BodyMesh"));
|
Super::EndPlay(EndPlayReason);
|
||||||
USceneComponent* bodyMesh = GetRootComponent();
|
}
|
||||||
FActorSpawnParameters camera_spawn_params;
|
|
||||||
camera_spawn_params.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn;
|
|
||||||
|
|
||||||
const auto& transform = vehicle_sim_api_->getNedTransform();
|
std::map<std::string, APIPCamera*> AFlyingPawn::getCameras() const
|
||||||
for (const auto& camera_setting_pair : vehicle_sim_api_->getVehicleSettings().cameras) {
|
{
|
||||||
const auto& setting = camera_setting_pair.second;
|
std::map<std::string, APIPCamera*> cameras;
|
||||||
|
|
||||||
FVector position = transform.fromLocalNed(
|
cameras["0"] = cameras["front_center"] = fpv_camera_front_center_;
|
||||||
NedTransform::Vector3r(setting.position.x, setting.position.y, setting.position.z))
|
cameras["1"] = cameras["front_right"] = fpv_camera_front_right_;
|
||||||
- transform.fromLocalNed(NedTransform::Vector3r(0.0, 0.0, 0.0));
|
cameras["2"] = cameras["front_left"] = fpv_camera_front_left_;
|
||||||
|
cameras["3"] = cameras["bottom_center"] = fpv_camera_bottom_center_;
|
||||||
|
cameras["4"] = cameras["back_center"] = fpv_camera_back_center_;
|
||||||
|
|
||||||
FTransform camera_transform(FRotator(setting.rotation.pitch, setting.rotation.yaw, setting.rotation.roll),
|
return cameras;
|
||||||
position, FVector(1., 1., 1.));
|
|
||||||
|
|
||||||
APIPCamera* camera = this->GetWorld()->SpawnActor<APIPCamera>(pip_camera_class_, camera_transform, camera_spawn_params);
|
|
||||||
camera->AttachToComponent(bodyMesh, FAttachmentTransformRules::KeepRelativeTransform);
|
|
||||||
|
|
||||||
cameras_[camera_setting_pair.first] = camera;
|
|
||||||
}
|
|
||||||
|
|
||||||
for (auto i = 0; i < rotor_count; ++i) {
|
|
||||||
rotating_movements_[i] = UAirBlueprintLib::GetActorComponent<URotatingMovementComponent>(this, TEXT("Rotation") + FString::FromInt(i));
|
|
||||||
}
|
|
||||||
|
|
||||||
vehicle_sim_api_->setupCamerasFromSettings();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AFlyingPawn::NotifyHit(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
void AFlyingPawn::NotifyHit(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
||||||
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit)
|
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit)
|
||||||
{
|
{
|
||||||
vehicle_sim_api_->onCollision(MyComp, Other, OtherComp, bSelfMoved, HitLocation,
|
collision_signal_.emit(MyComp, Other, OtherComp, bSelfMoved, HitLocation,
|
||||||
HitNormal, NormalImpulse, Hit);
|
HitNormal, NormalImpulse, Hit);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,11 +1,9 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "VehicleSimApi.h"
|
|
||||||
#include "GameFramework/RotatingMovementComponent.h"
|
#include "GameFramework/RotatingMovementComponent.h"
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include "vehicles/multirotor/api/MultirotorCommon.hpp"
|
|
||||||
#include "PIPCamera.h"
|
#include "PIPCamera.h"
|
||||||
#include "api/VehicleSimApiBase.hpp"
|
#include "common/common_utils/Signal.hpp"
|
||||||
#include "FlyingPawn.generated.h"
|
#include "FlyingPawn.generated.h"
|
||||||
|
|
||||||
UCLASS()
|
UCLASS()
|
||||||
|
@ -14,28 +12,27 @@ class AIRSIM_API AFlyingPawn : public APawn
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
public:
|
public:
|
||||||
AFlyingPawn();
|
typedef common_utils::Signal<class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
||||||
|
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit> CollisionSignal;
|
||||||
|
|
||||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Debugging")
|
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Debugging")
|
||||||
float RotatorFactor = 1.0f;
|
float RotatorFactor = 1.0f;
|
||||||
|
|
||||||
void setRotorSpeed(int rotor_index, float radsPerSec);
|
|
||||||
void initializeForBeginPlay(const NedTransform& global_transform, const std::string& vehicle_name);
|
|
||||||
|
|
||||||
virtual void BeginPlay() override;
|
virtual void BeginPlay() override;
|
||||||
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
||||||
virtual void NotifyHit(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
virtual void NotifyHit(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
||||||
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit) override;
|
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit) override;
|
||||||
|
|
||||||
msr::airlib::VehicleSimApiBase* getVehicleSimApi()
|
//interface
|
||||||
{
|
void initializeForBeginPlay();
|
||||||
return vehicle_sim_api_.get();
|
std::map<std::string, APIPCamera*> getCameras() const;
|
||||||
}
|
CollisionSignal& getCollisionSignal();
|
||||||
|
//called by API to set rotor speed
|
||||||
|
void setRotorSpeed(int rotor_index, float radsPerSec);
|
||||||
|
|
||||||
|
|
||||||
private: //variables
|
private: //variables
|
||||||
UPROPERTY() UClass* pip_camera_class_;
|
//Unreal components
|
||||||
|
|
||||||
//Unreal components
|
|
||||||
static constexpr size_t rotor_count = 4;
|
static constexpr size_t rotor_count = 4;
|
||||||
UPROPERTY() APIPCamera* fpv_camera_front_left_;
|
UPROPERTY() APIPCamera* fpv_camera_front_left_;
|
||||||
UPROPERTY() APIPCamera* fpv_camera_front_right_;
|
UPROPERTY() APIPCamera* fpv_camera_front_right_;
|
||||||
|
@ -45,6 +42,5 @@ private: //variables
|
||||||
|
|
||||||
UPROPERTY() URotatingMovementComponent* rotating_movements_[rotor_count];
|
UPROPERTY() URotatingMovementComponent* rotating_movements_[rotor_count];
|
||||||
|
|
||||||
std::map<std::string, APIPCamera*> cameras_;
|
CollisionSignal collision_signal_;
|
||||||
std::_Unique_ptr_base<msr::airlib::VehicleSimApiBase> vehicle_sim_api_;
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,16 +1,16 @@
|
||||||
#include "MultirotorSimApi.h"
|
#include "MultirotorSimApi.h"
|
||||||
#include "FlyingPawn.h"
|
|
||||||
#include "AirBlueprintLib.h"
|
#include "AirBlueprintLib.h"
|
||||||
|
#include "vehicles/multirotor/MultiRotorParamsFactory.hpp"
|
||||||
|
#include "UnrealSensors/UnrealSensorFactory.h"
|
||||||
#include <exception>
|
#include <exception>
|
||||||
|
|
||||||
using namespace msr::airlib;
|
using namespace msr::airlib;
|
||||||
|
|
||||||
MultirotorSimApi::MultirotorSimApi(msr::airlib::MultirotorApiBase* vehicle_api, msr::airlib::MultiRotorParams* vehicle_params,
|
MultirotorSimApi::MultirotorSimApi(APawn* pawn, const NedTransform& global_transform, CollisionSignal& collision_signal,
|
||||||
UManualPoseController* manual_pose_controller,
|
const std::map<std::string, APIPCamera*>& cameras,
|
||||||
APawn* pawn, const std::map<std::string, APIPCamera*>* cameras, const NedTransform& global_transform,
|
UManualPoseController* manual_pose_controller)
|
||||||
const std::string& vehicle_name)
|
: VehicleSimApi(pawn, global_transform, collision_signal, cameras),
|
||||||
: VehicleSimApi(pawn, cameras, global_transform, vehicle_name), vehicle_api_(vehicle_api),
|
manual_pose_controller_(manual_pose_controller)
|
||||||
vehicle_params_(vehicle_params), manual_pose_controller_(manual_pose_controller)
|
|
||||||
{
|
{
|
||||||
//reset roll & pitch of vehicle as multirotors required to be on plain surface at start
|
//reset roll & pitch of vehicle as multirotors required to be on plain surface at start
|
||||||
Pose pose = getPose();
|
Pose pose = getPose();
|
||||||
|
@ -19,6 +19,8 @@ MultirotorSimApi::MultirotorSimApi(msr::airlib::MultirotorApiBase* vehicle_api,
|
||||||
pose.orientation = VectorMath::toQuaternion(0, 0, yaw);
|
pose.orientation = VectorMath::toQuaternion(0, 0, yaw);
|
||||||
setPose(pose, false);
|
setPose(pose, false);
|
||||||
|
|
||||||
|
createVehicleApi();
|
||||||
|
|
||||||
//setup physics vehicle
|
//setup physics vehicle
|
||||||
phys_vehicle_ = std::unique_ptr<MultiRotor>(new MultiRotor(vehicle_params_, vehicle_api_,
|
phys_vehicle_ = std::unique_ptr<MultiRotor>(new MultiRotor(vehicle_params_, vehicle_api_,
|
||||||
getPose()));
|
getPose()));
|
||||||
|
@ -32,6 +34,19 @@ MultirotorSimApi::MultirotorSimApi(msr::airlib::MultirotorApiBase* vehicle_api,
|
||||||
did_reset_ = false;
|
did_reset_ = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void MultirotorSimApi::createVehicleApi()
|
||||||
|
{
|
||||||
|
//create vehicle params
|
||||||
|
std::shared_ptr<UnrealSensorFactory> sensor_factory = std::make_shared<UnrealSensorFactory>(getPawn(), &getNedTransform());
|
||||||
|
vehicle_params_ = MultiRotorParamsFactory::createConfig(getVehicleSetting(), sensor_factory);
|
||||||
|
vehicle_api_ = vehicle_params_->createMultirotorApi();
|
||||||
|
}
|
||||||
|
|
||||||
|
const msr::airlib::Kinematics::State* MultirotorSimApi::getGroundTruthKinematics() const
|
||||||
|
{
|
||||||
|
return & phys_vehicle_->getKinematics();
|
||||||
|
}
|
||||||
|
|
||||||
void MultirotorSimApi::updateRenderedState(float dt)
|
void MultirotorSimApi::updateRenderedState(float dt)
|
||||||
{
|
{
|
||||||
//Utils::log("------Render tick-------");
|
//Utils::log("------Render tick-------");
|
||||||
|
|
|
@ -8,8 +8,6 @@
|
||||||
#include "common/Common.hpp"
|
#include "common/Common.hpp"
|
||||||
#include "common/CommonStructs.hpp"
|
#include "common/CommonStructs.hpp"
|
||||||
#include "ManualPoseController.h"
|
#include "ManualPoseController.h"
|
||||||
#include <chrono>
|
|
||||||
#include <future>
|
|
||||||
|
|
||||||
|
|
||||||
class MultirotorSimApi : public VehicleSimApi
|
class MultirotorSimApi : public VehicleSimApi
|
||||||
|
@ -28,10 +26,9 @@ public:
|
||||||
|
|
||||||
//VehicleSimApiBase interface
|
//VehicleSimApiBase interface
|
||||||
//implements game interface to update pawn
|
//implements game interface to update pawn
|
||||||
MultirotorSimApi(msr::airlib::MultirotorApiBase* vehicle_api, msr::airlib::MultiRotorParams* vehicle_params,
|
MultirotorSimApi(APawn* pawn, const NedTransform& global_transform, CollisionSignal& collision_signal,
|
||||||
UManualPoseController* manual_pose_controller,
|
const std::map<std::string, APIPCamera*>& cameras,
|
||||||
APawn* pawn, const std::map<std::string, APIPCamera*>* cameras, const NedTransform& global_transform,
|
UManualPoseController* manual_pose_controller);
|
||||||
const std::string& vehicle_name);
|
|
||||||
virtual void updateRenderedState(float dt) override;
|
virtual void updateRenderedState(float dt) override;
|
||||||
virtual void updateRendering(float dt) override;
|
virtual void updateRendering(float dt) override;
|
||||||
|
|
||||||
|
@ -43,10 +40,19 @@ public:
|
||||||
virtual UpdatableObject* getPhysicsBody() override;
|
virtual UpdatableObject* getPhysicsBody() override;
|
||||||
|
|
||||||
virtual void setPose(const Pose& pose, bool ignore_collision) override;
|
virtual void setPose(const Pose& pose, bool ignore_collision) override;
|
||||||
|
virtual const msr::airlib::Kinematics::State* getGroundTruthKinematics() const override;
|
||||||
|
|
||||||
|
msr::airlib::MultirotorApiBase* getVehicleApi()
|
||||||
|
{
|
||||||
|
return vehicle_api_.get();
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
msr::airlib::MultirotorApiBase* vehicle_api_;
|
void createVehicleApi();
|
||||||
msr::airlib::MultiRotorParams* vehicle_params_;
|
|
||||||
|
private:
|
||||||
|
std::unique_ptr<msr::airlib::MultirotorApiBase> vehicle_api_;
|
||||||
|
std::unique_ptr<msr::airlib::MultiRotorParams> vehicle_params_;
|
||||||
UManualPoseController* manual_pose_controller_;
|
UManualPoseController* manual_pose_controller_;
|
||||||
|
|
||||||
std::unique_ptr<MultiRotor> phys_vehicle_;
|
std::unique_ptr<MultiRotor> phys_vehicle_;
|
||||||
|
|
|
@ -6,11 +6,11 @@
|
||||||
|
|
||||||
#include "AirBlueprintLib.h"
|
#include "AirBlueprintLib.h"
|
||||||
#include "vehicles/multirotor/api/MultirotorApiBase.hpp"
|
#include "vehicles/multirotor/api/MultirotorApiBase.hpp"
|
||||||
|
#include "MultirotorSimApi.h"
|
||||||
#include "physics/PhysicsBody.hpp"
|
#include "physics/PhysicsBody.hpp"
|
||||||
#include "common/ClockFactory.hpp"
|
#include "common/ClockFactory.hpp"
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include "vehicles/multirotor/MultiRotorParamsFactory.hpp"
|
|
||||||
#include "UnrealSensors/UnrealSensorFactory.h"
|
|
||||||
|
|
||||||
#ifndef AIRLIB_NO_RPC
|
#ifndef AIRLIB_NO_RPC
|
||||||
|
|
||||||
|
@ -38,16 +38,11 @@ ASimModeWorldMultiRotor::ASimModeWorldMultiRotor()
|
||||||
void ASimModeWorldMultiRotor::BeginPlay()
|
void ASimModeWorldMultiRotor::BeginPlay()
|
||||||
{
|
{
|
||||||
Super::BeginPlay();
|
Super::BeginPlay();
|
||||||
}
|
|
||||||
|
|
||||||
std::unique_ptr<msr::airlib::ApiServerBase> ASimModeWorldMultiRotor::createApiServer() const
|
setupVehiclesAndCamera();
|
||||||
{
|
|
||||||
#ifdef AIRLIB_NO_RPC
|
//let base class setup physics world
|
||||||
return ASimModeBase::createApiServer();
|
initializeForPlay();
|
||||||
#else
|
|
||||||
return std::unique_ptr<msr::airlib::ApiServerBase>(new msr::airlib::MultirotorRpcLibServer(
|
|
||||||
getApiProvider(), getSettings().api_server_address));
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ASimModeWorldMultiRotor::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
void ASimModeWorldMultiRotor::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||||
|
@ -55,26 +50,21 @@ void ASimModeWorldMultiRotor::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||||
//stop physics thread before we dismantle
|
//stop physics thread before we dismantle
|
||||||
stopAsyncUpdator();
|
stopAsyncUpdator();
|
||||||
|
|
||||||
//for (AActor* actor : spawned_actors_) {
|
external_camera_class_ = nullptr;
|
||||||
// actor->Destroy();
|
camera_director_class_ = nullptr;
|
||||||
//}
|
|
||||||
spawned_actors_.Empty();
|
vehicle_sim_apis_.clear();
|
||||||
//fpv_vehicle_connectors_.Empty();
|
spawned_actors_.RemoveAll();
|
||||||
CameraDirector = nullptr;
|
|
||||||
|
|
||||||
Super::EndPlay(EndPlayReason);
|
Super::EndPlay(EndPlayReason);
|
||||||
}
|
}
|
||||||
|
|
||||||
VehicleSimApi* ASimModeWorldMultiRotor::getFpvVehicleSimApi() const
|
void ASimModeWorldMultiRotor::setupVehiclesAndCamera()
|
||||||
{
|
{
|
||||||
return fpv_vehicle_sim_api_;
|
//get UU origin of global NED frame
|
||||||
}
|
|
||||||
|
|
||||||
void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles)
|
|
||||||
{
|
|
||||||
//put camera little bit above vehicle
|
|
||||||
//TODO: allow setting camera pose from settings
|
|
||||||
FVector uu_origin = getGlobalNedTransform().getLocalOffset();
|
FVector uu_origin = getGlobalNedTransform().getLocalOffset();
|
||||||
|
|
||||||
|
//TODO:make this configurable
|
||||||
FTransform camera_transform(uu_origin + FVector(-300, 0, 200));
|
FTransform camera_transform(uu_origin + FVector(-300, 0, 200));
|
||||||
|
|
||||||
//we will either find external camera if it already exist in environment or create one
|
//we will either find external camera if it already exist in environment or create one
|
||||||
|
@ -111,9 +101,12 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
|
||||||
TArray<AActor*> pawns;
|
TArray<AActor*> pawns;
|
||||||
UAirBlueprintLib::FindAllActor<TMultiRotorPawn>(this, pawns);
|
UAirBlueprintLib::FindAllActor<TMultiRotorPawn>(this, pawns);
|
||||||
|
|
||||||
|
TMultiRotorPawn* fpv_pawn = nullptr;
|
||||||
|
|
||||||
//add vehicles from settings
|
//add vehicles from settings
|
||||||
for (auto const& vehicle_setting_pair : getSettings().vehicles)
|
for (auto const& vehicle_setting_pair : getSettings().vehicles)
|
||||||
{
|
{
|
||||||
|
//if vehicle is of multirotor type and auto creatable
|
||||||
const auto& vehicle_setting = *vehicle_setting_pair.second;
|
const auto& vehicle_setting = *vehicle_setting_pair.second;
|
||||||
if (vehicle_setting.auto_create &&
|
if (vehicle_setting.auto_create &&
|
||||||
((vehicle_setting.vehicle_type == AirSimSettings::kVehicleTypeSimpleFlight) ||
|
((vehicle_setting.vehicle_type == AirSimSettings::kVehicleTypeSimpleFlight) ||
|
||||||
|
@ -124,15 +117,7 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
|
||||||
if (pawn_path == "")
|
if (pawn_path == "")
|
||||||
pawn_path = "DefaultQuadrotor";
|
pawn_path = "DefaultQuadrotor";
|
||||||
|
|
||||||
//create vehicle pawn
|
//compute initial pose
|
||||||
FActorSpawnParameters pawn_spawn_params;
|
|
||||||
pawn_spawn_params.Name = FName(vehicle_setting.vehicle_name.c_str());
|
|
||||||
pawn_spawn_params.SpawnCollisionHandlingOverride =
|
|
||||||
ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn;
|
|
||||||
|
|
||||||
auto vehicle_bp_class = UAirBlueprintLib::LoadClass(
|
|
||||||
getSettings().pawn_paths.at("DefaultQuadrotor").pawn_bp);
|
|
||||||
|
|
||||||
FVector spawn_position = uu_origin;
|
FVector spawn_position = uu_origin;
|
||||||
FRotator spawn_rotation = FRotator::ZeroRotator;
|
FRotator spawn_rotation = FRotator::ZeroRotator;
|
||||||
Vector3r settings_position = vehicle_setting.position;
|
Vector3r settings_position = vehicle_setting.position;
|
||||||
|
@ -145,51 +130,76 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
|
||||||
spawn_rotation.Pitch = rotation.pitch;
|
spawn_rotation.Pitch = rotation.pitch;
|
||||||
if (!std::isnan(rotation.roll))
|
if (!std::isnan(rotation.roll))
|
||||||
spawn_rotation.Roll = rotation.roll;
|
spawn_rotation.Roll = rotation.roll;
|
||||||
|
|
||||||
|
//spawn vehicle pawn
|
||||||
|
FActorSpawnParameters pawn_spawn_params;
|
||||||
|
pawn_spawn_params.Name = FName(vehicle_setting.vehicle_name.c_str());
|
||||||
|
pawn_spawn_params.SpawnCollisionHandlingOverride =
|
||||||
|
ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn;
|
||||||
|
auto vehicle_bp_class = UAirBlueprintLib::LoadClass(
|
||||||
|
getSettings().pawn_paths.at("DefaultQuadrotor").pawn_bp);
|
||||||
TMultiRotorPawn* spawned_pawn = this->GetWorld()->SpawnActor<TMultiRotorPawn>(
|
TMultiRotorPawn* spawned_pawn = this->GetWorld()->SpawnActor<TMultiRotorPawn>(
|
||||||
vehicle_bp_class, FTransform(spawn_rotation, spawn_position), pawn_spawn_params);
|
vehicle_bp_class, FTransform(spawn_rotation, spawn_position), pawn_spawn_params);
|
||||||
|
|
||||||
spawned_actors_.Add(spawned_pawn);
|
spawned_actors_.Add(spawned_pawn);
|
||||||
pawns.Add(spawned_pawn);
|
pawns.Add(spawned_pawn);
|
||||||
|
|
||||||
|
if (vehicle_setting.is_fpv_vehicle)
|
||||||
|
fpv_pawn = spawned_pawn;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//set up vehicle pawns
|
//create API objects for each pawn we have
|
||||||
fpv_vehicle_sim_api_ = nullptr;
|
|
||||||
for (AActor* pawn : pawns)
|
for (AActor* pawn : pawns)
|
||||||
{
|
{
|
||||||
//initialize each vehicle pawn we found
|
//initialize the pawn
|
||||||
TMultiRotorPawn* vehicle_pawn = static_cast<TMultiRotorPawn*>(pawn);
|
TMultiRotorPawn* vehicle_pawn = static_cast<TMultiRotorPawn*>(pawn);
|
||||||
vehicle_pawn->initializeForBeginPlay(getGlobalNedTransform(), std::string(TCHAR_TO_UTF8(*this->GetName())));
|
vehicle_pawn->initializeForBeginPlay();
|
||||||
const auto* vehicle_sim_api = vehicle_pawn->getVehicleSimApi();
|
|
||||||
//chose first pawn as FPV if none is designated as FPV
|
|
||||||
if (vehicle_sim_api->getVehicleSetting().is_fpv_vehicle || fpv_vehicle_sim_api_ == nullptr)
|
|
||||||
fpv_vehicle_sim_api_ = vehicle_sim_api;
|
|
||||||
|
|
||||||
//now create the connector for each pawn
|
//create vehicle sim api
|
||||||
VehiclePtr vehicle = createVehicle(vehicle_sim_api);
|
auto vehicle_sim_api = std::unique_ptr<MultirotorSimApi>(new MultirotorSimApi(
|
||||||
if (vehicle != nullptr) {
|
vehicle_pawn, getGlobalNedTransform(),
|
||||||
vehicles.push_back(vehicle);
|
vehicle_pawn->getCollisionSignal(), vehicle_pawn->getCameras(),
|
||||||
fpv_vehicle_connectors_.Add(vehicle);
|
manual_pose_controller));
|
||||||
}
|
|
||||||
//else we don't have vehicle for this pawn
|
std::string vehicle_name = vehicle_sim_api->getVehicleName();
|
||||||
|
|
||||||
|
getApiProvider()->insert_or_assign(vehicle_name, vehicle_sim_api->getVehicleApi(),
|
||||||
|
vehicle_sim_api.get());
|
||||||
|
if ((fpv_pawn == vehicle_pawn || !getApiProvider()->hasDefaultVehicle()) && vehicle_name != "")
|
||||||
|
getApiProvider()->makeDefaultVehicle(vehicle_name);
|
||||||
|
|
||||||
|
vehicle_sim_apis_.push_back(std::move(vehicle_sim_api));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
fpv_vehicle_sim_api_->possess();
|
if (getApiProvider()->hasDefaultVehicle()) {
|
||||||
CameraDirector->initializeForBeginPlay(getInitialViewMode(), fpv_vehicle_sim_api_, external_camera);
|
//TODO: better handle no FPV vehicles scenario
|
||||||
|
getVehicleSimApi()->possess();
|
||||||
|
CameraDirector->initializeForBeginPlay(getInitialViewMode(), getVehicleSimApi(), external_camera);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void ASimModeWorldMultiRotor::Tick(float DeltaSeconds)
|
void ASimModeWorldMultiRotor::Tick(float DeltaSeconds)
|
||||||
{
|
{
|
||||||
Super::Tick(DeltaSeconds);
|
Super::Tick(DeltaSeconds);
|
||||||
|
|
||||||
getFpvVehicleSimApi()->setLogLine(getLogString());
|
getVehicleSimApi()->setLogLine(getLogString());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::unique_ptr<msr::airlib::ApiServerBase> ASimModeWorldMultiRotor::createApiServer() const
|
||||||
|
{
|
||||||
|
#ifdef AIRLIB_NO_RPC
|
||||||
|
return ASimModeBase::createApiServer();
|
||||||
|
#else
|
||||||
|
return std::unique_ptr<msr::airlib::ApiServerBase>(new msr::airlib::MultirotorRpcLibServer(
|
||||||
|
getApiProvider(), getSettings().api_server_address));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string ASimModeWorldMultiRotor::getLogString() const
|
std::string ASimModeWorldMultiRotor::getLogString() const
|
||||||
{
|
{
|
||||||
const msr::airlib::Kinematics::State* kinematics = getFpvVehicleSimApi()->getGroundTruthKinematics();
|
const msr::airlib::Kinematics::State* kinematics = getVehicleSimApi()->getGroundTruthKinematics();
|
||||||
uint64_t timestamp_millis = static_cast<uint64_t>(msr::airlib::ClockFactory::get()->nowNanos() / 1.0E6);
|
uint64_t timestamp_millis = static_cast<uint64_t>(msr::airlib::ClockFactory::get()->nowNanos() / 1.0E6);
|
||||||
|
|
||||||
//TODO: because this bug we are using alternative code with stringstream
|
//TODO: because this bug we are using alternative code with stringstream
|
||||||
|
@ -215,31 +225,10 @@ std::string ASimModeWorldMultiRotor::getLogString() const
|
||||||
//return ss.str();
|
//return ss.str();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ASimModeWorldMultiRotor::createVehicles(std::vector<VehiclePtr>& vehicles)
|
|
||||||
{
|
|
||||||
//find vehicles and cameras available in environment
|
|
||||||
//if none available then we will create one
|
|
||||||
setupVehiclesAndCamera(vehicles);
|
|
||||||
}
|
|
||||||
|
|
||||||
ASimModeWorldBase::VehiclePtr ASimModeWorldMultiRotor::createVehicle(VehicleSimApi* vehicle_sim_api)
|
|
||||||
{
|
|
||||||
std::shared_ptr<UnrealSensorFactory> sensor_factory = std::make_shared<UnrealSensorFactory>(vehicle_sim_api->getPawn(), &vehicle_sim_api->getNedTransform());
|
|
||||||
auto vehicle_params = MultiRotorParamsFactory::createConfig(vehicle_sim_api->getVehicleSetting(), sensor_factory);
|
|
||||||
|
|
||||||
vehicle_params_.push_back(std::move(vehicle_params));
|
|
||||||
|
|
||||||
std::shared_ptr<MultirotorSimApi> vehicle = std::make_shared<MultirotorSimApi>(
|
|
||||||
vehicle_sim_api, vehicle_params_.back().get(), manual_pose_controller);
|
|
||||||
|
|
||||||
if (vehicle->getPhysicsBody() != nullptr)
|
|
||||||
vehicle_sim_api->setKinematics(&(static_cast<PhysicsBody*>(vehicle->getPhysicsBody())->getKinematics()));
|
|
||||||
|
|
||||||
return std::static_pointer_cast<VehicleSimApiBase>(vehicle);
|
|
||||||
}
|
|
||||||
|
|
||||||
void ASimModeWorldMultiRotor::setupClockSpeed()
|
void ASimModeWorldMultiRotor::setupClockSpeed()
|
||||||
{
|
{
|
||||||
|
typedef msr::airlib::ClockFactory ClockFactory;
|
||||||
|
|
||||||
float clock_speed = getSettings().clock_speed;
|
float clock_speed = getSettings().clock_speed;
|
||||||
|
|
||||||
//setup clock in ClockFactory
|
//setup clock in ClockFactory
|
||||||
|
|
|
@ -4,10 +4,7 @@
|
||||||
|
|
||||||
#include "FlyingPawn.h"
|
#include "FlyingPawn.h"
|
||||||
#include "common/Common.hpp"
|
#include "common/Common.hpp"
|
||||||
#include "MultirotorSimApi.h"
|
|
||||||
#include "vehicles/multirotor/MultiRotorParams.hpp"
|
|
||||||
#include "SimMode/SimModeWorldBase.h"
|
#include "SimMode/SimModeWorldBase.h"
|
||||||
#include "VehicleSimApi.h"
|
|
||||||
#include "SimModeWorldMultiRotor.generated.h"
|
#include "SimModeWorldMultiRotor.generated.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -22,32 +19,26 @@ public:
|
||||||
|
|
||||||
virtual void Tick( float DeltaSeconds ) override;
|
virtual void Tick( float DeltaSeconds ) override;
|
||||||
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
||||||
VehicleSimApi* getFpvVehicleSimApi() const override;
|
|
||||||
std::string getLogString() const;
|
std::string getLogString() const;
|
||||||
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
typedef AFlyingPawn TMultiRotorPawn;
|
typedef AFlyingPawn TMultiRotorPawn;
|
||||||
|
|
||||||
virtual void createVehicles(std::vector<VehiclePtr>& vehicles) override;
|
|
||||||
VehiclePtr createVehicle(VehicleSimApi* vehicle_sim_api);
|
|
||||||
virtual void setupClockSpeed() override;
|
virtual void setupClockSpeed() override;
|
||||||
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const override;
|
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles);
|
void setupVehiclesAndCamera();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
typedef msr::airlib::ClockFactory ClockFactory;
|
//assets loaded in constructor
|
||||||
|
|
||||||
TArray<uint8> image_;
|
|
||||||
std::vector <std::unique_ptr<msr::airlib::MultiRotorParams> > vehicle_params_;
|
|
||||||
|
|
||||||
UClass* external_camera_class_;
|
UClass* external_camera_class_;
|
||||||
UClass* camera_director_class_;
|
UClass* camera_director_class_;
|
||||||
|
|
||||||
TArray<AActor*> spawned_actors_;
|
std::vector<std::unique_ptr<VehicleSimApiBase>>& vehicle_sim_apis_;
|
||||||
|
|
||||||
VehicleSimApi* fpv_vehicle_pawn_wrapper_;
|
UPROPERTY()
|
||||||
TArray <std::shared_ptr<VehicleSimApiBase> > fpv_vehicle_connectors_;
|
TArray<AActor*> spawned_actors_; //keep refs alive from Unreal GC
|
||||||
};
|
};
|
||||||
|
|
|
@ -86,7 +86,7 @@ void ASimHUD::inputEventToggleHelp()
|
||||||
|
|
||||||
void ASimHUD::inputEventToggleTrace()
|
void ASimHUD::inputEventToggleTrace()
|
||||||
{
|
{
|
||||||
simmode_->getFpvVehicleSimApi()->toggleTrace();
|
simmode_->getVehicleSimApi()->toggleTrace();
|
||||||
}
|
}
|
||||||
|
|
||||||
ASimHUD::ImageType ASimHUD::getSubwindowCameraType(int window_index)
|
ASimHUD::ImageType ASimHUD::getSubwindowCameraType(int window_index)
|
||||||
|
@ -291,7 +291,7 @@ void ASimHUD::createSimMode()
|
||||||
|
|
||||||
void ASimHUD::initializeSubWindows()
|
void ASimHUD::initializeSubWindows()
|
||||||
{
|
{
|
||||||
auto vehicle_sim_api = simmode_->getFpvVehicleSimApi();
|
auto vehicle_sim_api = simmode_->getVehicleSimApi();
|
||||||
auto camera_count = vehicle_sim_api->getCameraCount();
|
auto camera_count = vehicle_sim_api->getCameraCount();
|
||||||
|
|
||||||
//setup defaults
|
//setup defaults
|
||||||
|
|
|
@ -92,6 +92,8 @@ void ASimModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||||
{
|
{
|
||||||
FRecordingThread::stopRecording();
|
FRecordingThread::stopRecording();
|
||||||
world_sim_api_.reset(nullptr);
|
world_sim_api_.reset(nullptr);
|
||||||
|
CameraDirector = nullptr;
|
||||||
|
|
||||||
Super::EndPlay(EndPlayReason);
|
Super::EndPlay(EndPlayReason);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -259,13 +261,6 @@ void ASimModeBase::reset()
|
||||||
//Should be overridden by derived classes
|
//Should be overridden by derived classes
|
||||||
}
|
}
|
||||||
|
|
||||||
msr::airlib::VehicleSimApiBase* ASimModeBase::getFpvVehicleSimApi()
|
|
||||||
{
|
|
||||||
//Should be overridden by derived classes
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
std::string ASimModeBase::getDebugReport()
|
std::string ASimModeBase::getDebugReport()
|
||||||
{
|
{
|
||||||
static const std::string empty_string = std::string();
|
static const std::string empty_string = std::string();
|
||||||
|
@ -307,9 +302,9 @@ void ASimModeBase::stopRecording()
|
||||||
|
|
||||||
void ASimModeBase::startRecording()
|
void ASimModeBase::startRecording()
|
||||||
{
|
{
|
||||||
FRecordingThread::startRecording(getFpvVehicleSimApi()->getImageCapture(),
|
FRecordingThread::startRecording(getVehicleSimApi()->getImageCapture(),
|
||||||
getFpvVehicleSimApi()->getGroundTruthKinematics(), getSettings().segmentation_setting,
|
getVehicleSimApi()->getGroundTruthKinematics(), getSettings().recording_setting ,
|
||||||
getFpvVehicleSimApi());
|
getVehicleSimApi());
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ASimModeBase::isRecording() const
|
bool ASimModeBase::isRecording() const
|
||||||
|
@ -325,7 +320,7 @@ void ASimModeBase::startApiServer()
|
||||||
#ifdef AIRLIB_NO_RPC
|
#ifdef AIRLIB_NO_RPC
|
||||||
api_server_.reset();
|
api_server_.reset();
|
||||||
#else
|
#else
|
||||||
api_provider_.reset(new msr::airlib::ApiProvider(world_sim_api_.get()));
|
api_provider_.reset(new msr::airlib::ApiProvider<VehicleSimApi>(world_sim_api_.get()));
|
||||||
api_server_ = createApiServer();
|
api_server_ = createApiServer();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -11,7 +11,7 @@
|
||||||
#include "common/ClockFactory.hpp"
|
#include "common/ClockFactory.hpp"
|
||||||
#include "api/ApiServerBase.hpp"
|
#include "api/ApiServerBase.hpp"
|
||||||
#include "api/ApiProvider.hpp"
|
#include "api/ApiProvider.hpp"
|
||||||
#include "api/VehicleSimApiBase.hpp"
|
#include "VehicleSimApi.h"
|
||||||
#include "SimModeBase.generated.h"
|
#include "SimModeBase.generated.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -41,8 +41,6 @@ public:
|
||||||
//additional overridable methods
|
//additional overridable methods
|
||||||
virtual void reset();
|
virtual void reset();
|
||||||
virtual std::string getDebugReport();
|
virtual std::string getDebugReport();
|
||||||
msr::airlib::VehicleSimApiBase* ASimModeBase::getFpvVehicleSimApi();
|
|
||||||
|
|
||||||
virtual ECameraDirectorMode getInitialViewMode() const;
|
virtual ECameraDirectorMode getInitialViewMode() const;
|
||||||
|
|
||||||
virtual bool isPaused() const;
|
virtual bool isPaused() const;
|
||||||
|
@ -59,6 +57,20 @@ public:
|
||||||
|
|
||||||
const NedTransform& getGlobalNedTransform();
|
const NedTransform& getGlobalNedTransform();
|
||||||
|
|
||||||
|
msr::airlib::ApiProvider* getApiProvider() const
|
||||||
|
{
|
||||||
|
return api_provider_.get();
|
||||||
|
}
|
||||||
|
|
||||||
|
const VehicleSimApi* getVehicleSimApi(const std::string& vehicle_name = "") const
|
||||||
|
{
|
||||||
|
return static_cast<VehicleSimApi*>(api_provider_->getVehicleSimApi(vehicle_name));
|
||||||
|
}
|
||||||
|
VehicleSimApi* getVehicleSimApi(const std::string& vehicle_name = "")
|
||||||
|
{
|
||||||
|
return static_cast<VehicleSimApi*>(api_provider_->getVehicleSimApi(vehicle_name));
|
||||||
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual void setupInputBindings();
|
virtual void setupInputBindings();
|
||||||
virtual const msr::airlib::AirSimSettings& getSettings() const;
|
virtual const msr::airlib::AirSimSettings& getSettings() const;
|
||||||
|
@ -67,10 +79,6 @@ protected:
|
||||||
virtual void setupClockSpeed();
|
virtual void setupClockSpeed();
|
||||||
|
|
||||||
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const;
|
virtual std::unique_ptr<msr::airlib::ApiServerBase> createApiServer() const;
|
||||||
msr::airlib::ApiProvider* getApiProvider() const
|
|
||||||
{
|
|
||||||
return api_provider_.get();
|
|
||||||
}
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
typedef msr::airlib::AirSimSettings AirSimSettings;
|
typedef msr::airlib::AirSimSettings AirSimSettings;
|
||||||
|
|
|
@ -9,27 +9,25 @@ void ASimModeWorldBase::BeginPlay()
|
||||||
|
|
||||||
manual_pose_controller = NewObject<UManualPoseController>();
|
manual_pose_controller = NewObject<UManualPoseController>();
|
||||||
setupInputBindings();
|
setupInputBindings();
|
||||||
|
}
|
||||||
|
|
||||||
//call virtual method in derived class
|
void ASimModeWorldBase::initializeForPlay()
|
||||||
createVehicles(vehicles_);
|
{
|
||||||
|
|
||||||
physics_world_.reset(new msr::airlib::PhysicsWorld(
|
physics_world_.reset(new msr::airlib::PhysicsWorld(
|
||||||
createPhysicsEngine(), toUpdatableObjects(vehicles_),
|
createPhysicsEngine(), toUpdatableObjects(vehicles_),
|
||||||
getPhysicsLoopPeriod()));
|
getPhysicsLoopPeriod()));
|
||||||
|
|
||||||
if (getSettings().usage_scenario == kUsageScenarioComputerVision) {
|
if (getSettings().usage_scenario == kUsageScenarioComputerVision) {
|
||||||
manual_pose_controller->initializeForPlay();
|
manual_pose_controller->initializeForPlay();
|
||||||
manual_pose_controller->setActor(getFpvVehicleSimApi()->getPawn());
|
manual_pose_controller->setActor(getVehicleSimApi()->getPawn());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void ASimModeWorldBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
void ASimModeWorldBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||||
{
|
{
|
||||||
//remove everything that we created in BeginPlay
|
//remove everything that we created in BeginPlay
|
||||||
physics_world_.reset();
|
physics_world_.reset();
|
||||||
physics_engine_.reset();
|
physics_engine_.reset();
|
||||||
vehicles_.clear();
|
|
||||||
manual_pose_controller = nullptr;
|
manual_pose_controller = nullptr;
|
||||||
|
|
||||||
Super::EndPlay(EndPlayReason);
|
Super::EndPlay(EndPlayReason);
|
||||||
|
@ -98,11 +96,6 @@ void ASimModeWorldBase::continueForTime(double seconds)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t ASimModeWorldBase::getVehicleCount() const
|
|
||||||
{
|
|
||||||
return vehicles_.size();
|
|
||||||
}
|
|
||||||
|
|
||||||
void ASimModeWorldBase::Tick(float DeltaSeconds)
|
void ASimModeWorldBase::Tick(float DeltaSeconds)
|
||||||
{
|
{
|
||||||
{ //keep this lock as short as possible
|
{ //keep this lock as short as possible
|
||||||
|
@ -111,15 +104,15 @@ void ASimModeWorldBase::Tick(float DeltaSeconds)
|
||||||
physics_world_->enableStateReport(EnableReport);
|
physics_world_->enableStateReport(EnableReport);
|
||||||
physics_world_->updateStateReport();
|
physics_world_->updateStateReport();
|
||||||
|
|
||||||
for (auto& vehicle : vehicles_)
|
for (auto& pair : getApiProvider()->getVehicleSimApis())
|
||||||
vehicle->updateRenderedState(DeltaSeconds);
|
pair.second->updateRenderedState(DeltaSeconds);
|
||||||
|
|
||||||
physics_world_->unlock();
|
physics_world_->unlock();
|
||||||
}
|
}
|
||||||
|
|
||||||
//perfom any expensive rendering update outside of lock region
|
//perform any expensive rendering update outside of lock region
|
||||||
for (auto& vehicle : vehicles_)
|
for (auto& pair : getApiProvider()->getVehicleSimApis())
|
||||||
vehicle->updateRendering(DeltaSeconds);
|
pair.second->updateRendering(DeltaSeconds);
|
||||||
|
|
||||||
Super::Tick(DeltaSeconds);
|
Super::Tick(DeltaSeconds);
|
||||||
}
|
}
|
||||||
|
@ -138,9 +131,4 @@ std::string ASimModeWorldBase::getDebugReport()
|
||||||
return physics_world_->getDebugReport();
|
return physics_world_->getDebugReport();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ASimModeWorldBase::createVehicles(std::vector<VehiclePtr>& vehicles)
|
|
||||||
{
|
|
||||||
//should be overridden by derived class
|
|
||||||
//Unreal doesn't allow pure abstract methods in actors
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
|
@ -33,27 +33,26 @@ public:
|
||||||
virtual void continueForTime(double seconds) override;
|
virtual void continueForTime(double seconds) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
typedef std::shared_ptr<msr::airlib::VehicleSimApiBase> VehiclePtr;
|
|
||||||
virtual void createVehicles(std::vector<VehiclePtr>& vehicles);
|
|
||||||
size_t getVehicleCount() const;
|
|
||||||
|
|
||||||
UPROPERTY() UManualPoseController* manual_pose_controller;
|
UPROPERTY() UManualPoseController* manual_pose_controller;
|
||||||
|
|
||||||
void startAsyncUpdator();
|
void startAsyncUpdator();
|
||||||
void stopAsyncUpdator();
|
void stopAsyncUpdator();
|
||||||
|
|
||||||
|
//should be called by derived class once all api_provider_ is ready to use
|
||||||
|
void initializeForPlay();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
typedef msr::airlib::UpdatableObject UpdatableObject;
|
typedef msr::airlib::UpdatableObject UpdatableObject;
|
||||||
typedef msr::airlib::PhysicsEngineBase PhysicsEngineBase;
|
typedef msr::airlib::PhysicsEngineBase PhysicsEngineBase;
|
||||||
typedef msr::airlib::ClockFactory ClockFactory;
|
typedef msr::airlib::ClockFactory ClockFactory;
|
||||||
|
|
||||||
|
//create the physics engine as needed from settings
|
||||||
PhysicsEngineBase* createPhysicsEngine();
|
PhysicsEngineBase* createPhysicsEngine();
|
||||||
|
|
||||||
|
|
||||||
static std::vector<UpdatableObject*> toUpdatableObjects(const std::vector<VehiclePtr>& vehicles);
|
static std::vector<UpdatableObject*> toUpdatableObjects(const std::vector<VehiclePtr>& vehicles);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::unique_ptr<msr::airlib::PhysicsWorld> physics_world_;
|
std::unique_ptr<msr::airlib::PhysicsWorld> physics_world_;
|
||||||
|
|
||||||
std::unique_ptr<PhysicsEngineBase> physics_engine_;
|
std::unique_ptr<PhysicsEngineBase> physics_engine_;
|
||||||
|
|
||||||
std::vector<VehiclePtr> vehicles_;
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,22 +1,27 @@
|
||||||
#include "VehicleSimApi.h"
|
#include "VehicleSimApi.h"
|
||||||
|
#include "Engine/World.h"
|
||||||
#include "Kismet/KismetSystemLibrary.h"
|
#include "Kismet/KismetSystemLibrary.h"
|
||||||
#include "Kismet/GameplayStatics.h"
|
#include "Kismet/GameplayStatics.h"
|
||||||
#include "Particles/ParticleSystemComponent.h"
|
#include "Particles/ParticleSystemComponent.h"
|
||||||
#include "ConstructorHelpers.h"
|
#include "ConstructorHelpers.h"
|
||||||
|
|
||||||
#include "AirBlueprintLib.h"
|
#include "AirBlueprintLib.h"
|
||||||
#include "common/ClockFactory.hpp"
|
#include "common/ClockFactory.hpp"
|
||||||
|
#include "PIPCamera.h"
|
||||||
#include "NedTransform.h"
|
#include "NedTransform.h"
|
||||||
#include "common/EarthUtils.hpp"
|
#include "common/EarthUtils.hpp"
|
||||||
|
|
||||||
VehicleSimApi::VehicleSimApi(APawn* pawn, const std::map<std::string, APIPCamera*>* cameras, const NedTransform& global_transform,
|
VehicleSimApi::VehicleSimApi(APawn* pawn, const NedTransform& global_transform, CollisionSignal& collision_signal,
|
||||||
const std::string& vehicle_name)
|
const std::map<std::string, APIPCamera*>& cameras)
|
||||||
: pawn_(pawn), cameras_(cameras), vehicle_name_(vehicle_name), ned_transform_(pawn, global_transform)
|
: pawn_(pawn), vehicle_name_(TCHAR_TO_UTF8(*pawn->GetName())), ned_transform_(pawn, global_transform)
|
||||||
{
|
{
|
||||||
static ConstructorHelpers::FObjectFinder<UParticleSystem> collision_display(TEXT("ParticleSystem'/AirSim/StarterContent/Particles/P_Explosion.P_Explosion'"));
|
static ConstructorHelpers::FObjectFinder<UParticleSystem> collision_display(TEXT("ParticleSystem'/AirSim/StarterContent/Particles/P_Explosion.P_Explosion'"));
|
||||||
if (!collision_display.Succeeded())
|
if (!collision_display.Succeeded())
|
||||||
collision_display_template = collision_display.Object;
|
collision_display_template = collision_display.Object;
|
||||||
else
|
else
|
||||||
collision_display_template = nullptr;
|
collision_display_template = nullptr;
|
||||||
|
static ConstructorHelpers::FClassFinder<APIPCamera> pip_camera_class(TEXT("Blueprint'/AirSim/Blueprints/BP_PIPCamera'"));
|
||||||
|
pip_camera_class_ = pip_camera_class.Succeeded() ? pip_camera_class.Class : nullptr;
|
||||||
|
|
||||||
image_capture_.reset(new UnrealImageCapture(cameras_));
|
image_capture_.reset(new UnrealImageCapture(cameras_));
|
||||||
|
|
||||||
|
@ -36,9 +41,9 @@ VehicleSimApi::VehicleSimApi(APawn* pawn, const std::map<std::string, APIPCamera
|
||||||
Vector3r nedWrtOrigin = ned_transform_.toGlobalNed(getUUPosition());
|
Vector3r nedWrtOrigin = ned_transform_.toGlobalNed(getUUPosition());
|
||||||
home_geo_point_ = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, AirSimSettings::singleton().origin_geopoint);
|
home_geo_point_ = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, AirSimSettings::singleton().origin_geopoint);
|
||||||
|
|
||||||
initial_state_.tracing_enabled = getVehicleSetting().enable_trace;
|
initial_state_.tracing_enabled = getVehicleSetting()->enable_trace;
|
||||||
initial_state_.collisions_enabled = getVehicleSetting().enable_collisions;
|
initial_state_.collisions_enabled = getVehicleSetting()->enable_collisions;
|
||||||
initial_state_.passthrough_enabled = getVehicleSetting().enable_collision_passthrough;
|
initial_state_.passthrough_enabled = getVehicleSetting()->enable_collision_passthrough;
|
||||||
|
|
||||||
initial_state_.collision_info = CollisionInfo();
|
initial_state_.collision_info = CollisionInfo();
|
||||||
|
|
||||||
|
@ -48,6 +53,10 @@ VehicleSimApi::VehicleSimApi(APawn* pawn, const std::map<std::string, APIPCamera
|
||||||
//setup RC
|
//setup RC
|
||||||
if (getRemoteControlID() >= 0)
|
if (getRemoteControlID() >= 0)
|
||||||
detectUsbRc();
|
detectUsbRc();
|
||||||
|
|
||||||
|
setupCamerasFromSettings(cameras);
|
||||||
|
//add listener for pawn's collision event
|
||||||
|
collision_signal.connect(this, &VehicleSimApi::onCollision);
|
||||||
}
|
}
|
||||||
|
|
||||||
void VehicleSimApi::detectUsbRc()
|
void VehicleSimApi::detectUsbRc()
|
||||||
|
@ -63,20 +72,54 @@ void VehicleSimApi::detectUsbRc()
|
||||||
std::to_string(joystick_state_.connection_error_code), LogDebugLevel::Informational);
|
std::to_string(joystick_state_.connection_error_code), LogDebugLevel::Informational);
|
||||||
}
|
}
|
||||||
|
|
||||||
void VehicleSimApi::setupCamerasFromSettings()
|
void VehicleSimApi::setupCamerasFromSettings(const std::map<std::string, APIPCamera*>& cameras)
|
||||||
{
|
{
|
||||||
|
//add cameras that already exists in pawn
|
||||||
|
cameras_.clear();
|
||||||
|
for (const auto& p : cameras)
|
||||||
|
cameras_[p.first] = p.second;
|
||||||
|
|
||||||
|
//create or replace cameras specified in settings
|
||||||
|
createCamerasFromSettings();
|
||||||
|
|
||||||
|
//setup individual cameras
|
||||||
typedef msr::airlib::AirSimSettings AirSimSettings;
|
typedef msr::airlib::AirSimSettings AirSimSettings;
|
||||||
|
|
||||||
const auto& vehicle_setting = AirSimSettings::singleton().getVehicleSetting(vehicle_name_);
|
|
||||||
const auto& camera_defaults = AirSimSettings::singleton().camera_defaults;
|
const auto& camera_defaults = AirSimSettings::singleton().camera_defaults;
|
||||||
|
for (auto& pair : cameras_) {
|
||||||
for (auto& pair : *cameras_) {
|
const auto& camera_setting = Utils::findOrDefault(getVehicleSetting()->cameras, pair.first, camera_defaults);
|
||||||
const auto& camera_setting = Utils::findOrDefault(vehicle_setting->cameras, pair.first, camera_defaults);
|
|
||||||
APIPCamera* camera = pair.second;
|
APIPCamera* camera = pair.second;
|
||||||
camera->setupCameraFromSettings(camera_setting, getNedTransform());
|
camera->setupCameraFromSettings(camera_setting, getNedTransform());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void VehicleSimApi::createCamerasFromSettings()
|
||||||
|
{
|
||||||
|
//UStaticMeshComponent* bodyMesh = UAirBlueprintLib::GetActorComponent<UStaticMeshComponent>(this, TEXT("BodyMesh"));
|
||||||
|
USceneComponent* bodyMesh = pawn_->GetRootComponent();
|
||||||
|
FActorSpawnParameters camera_spawn_params;
|
||||||
|
camera_spawn_params.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn;
|
||||||
|
const auto& transform = getNedTransform();
|
||||||
|
|
||||||
|
//for each camera in settings
|
||||||
|
for (const auto& camera_setting_pair : getVehicleSetting()->cameras) {
|
||||||
|
const auto& setting = camera_setting_pair.second;
|
||||||
|
|
||||||
|
//get pose
|
||||||
|
FVector position = transform.fromLocalNed(
|
||||||
|
NedTransform::Vector3r(setting.position.x, setting.position.y, setting.position.z))
|
||||||
|
- transform.fromLocalNed(NedTransform::Vector3r(0.0, 0.0, 0.0));
|
||||||
|
FTransform camera_transform(FRotator(setting.rotation.pitch, setting.rotation.yaw, setting.rotation.roll),
|
||||||
|
position, FVector(1., 1., 1.));
|
||||||
|
|
||||||
|
//spawn and attach camera to pawn
|
||||||
|
APIPCamera* camera = pawn_->GetWorld()->SpawnActor<APIPCamera>(pip_camera_class_, camera_transform, camera_spawn_params);
|
||||||
|
camera->AttachToComponent(bodyMesh, FAttachmentTransformRules::KeepRelativeTransform);
|
||||||
|
|
||||||
|
//add on to our collection
|
||||||
|
cameras_[camera_setting_pair.first] = camera;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void VehicleSimApi::onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
void VehicleSimApi::onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
||||||
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit)
|
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit)
|
||||||
{
|
{
|
||||||
|
@ -208,7 +251,7 @@ void VehicleSimApi::setGroundTruthKinematics(const msr::airlib::Kinematics::Stat
|
||||||
|
|
||||||
int VehicleSimApi::getRemoteControlID() const
|
int VehicleSimApi::getRemoteControlID() const
|
||||||
{
|
{
|
||||||
return getVehicleSetting().rc.remote_control_id;
|
return getVehicleSetting()->rc.remote_control_id;
|
||||||
}
|
}
|
||||||
|
|
||||||
const APIPCamera* VehicleSimApi::getCamera(const std::string& camera_name) const
|
const APIPCamera* VehicleSimApi::getCamera(const std::string& camera_name) const
|
||||||
|
|
|
@ -7,6 +7,7 @@
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include "UnrealImageCapture.h"
|
#include "UnrealImageCapture.h"
|
||||||
#include "common/Common.hpp"
|
#include "common/Common.hpp"
|
||||||
|
#include "common/common_utils/Signal.hpp"
|
||||||
#include "common/CommonStructs.hpp"
|
#include "common/CommonStructs.hpp"
|
||||||
#include "PIPCamera.h"
|
#include "PIPCamera.h"
|
||||||
#include "physics/Kinematics.hpp"
|
#include "physics/Kinematics.hpp"
|
||||||
|
@ -28,7 +29,8 @@ public: //types
|
||||||
typedef msr::airlib::Utils Utils;
|
typedef msr::airlib::Utils Utils;
|
||||||
typedef msr::airlib::AirSimSettings::VehicleSetting VehicleSetting;
|
typedef msr::airlib::AirSimSettings::VehicleSetting VehicleSetting;
|
||||||
typedef msr::airlib::ImageCaptureBase ImageCaptureBase;
|
typedef msr::airlib::ImageCaptureBase ImageCaptureBase;
|
||||||
|
typedef common_utils::Signal<class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp, bool bSelfMoved, FVector HitLocation,
|
||||||
|
FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit> CollisionSignal;
|
||||||
|
|
||||||
public: //implementation of VehicleSimApiBase
|
public: //implementation of VehicleSimApiBase
|
||||||
virtual void reset() override;
|
virtual void reset() override;
|
||||||
|
@ -48,14 +50,12 @@ public: //implementation of VehicleSimApiBase
|
||||||
return vehicle_name_;
|
return vehicle_name_;
|
||||||
}
|
}
|
||||||
virtual std::string getLogLine() const override;
|
virtual std::string getLogLine() const override;
|
||||||
|
virtual void setLogLine(std::string line) override;
|
||||||
|
virtual void toggleTrace() override;
|
||||||
|
|
||||||
public: //Unreal specific methods
|
public: //Unreal specific methods
|
||||||
VehicleSimApi(APawn* pawn, const std::map<std::string, APIPCamera*>* cameras, const NedTransform& global_transform,
|
VehicleSimApi(APawn* pawn, const NedTransform& global_transform, CollisionSignal& collision_signal,
|
||||||
const std::string& vehicle_name);
|
const std::map<std::string, APIPCamera*>& cameras);
|
||||||
|
|
||||||
//on collision, pawns should update this
|
|
||||||
void onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp,
|
|
||||||
bool bSelfMoved, FVector HitLocation, FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit);
|
|
||||||
|
|
||||||
//returns one of the cameras attached to the pawn
|
//returns one of the cameras attached to the pawn
|
||||||
const APIPCamera* getCamera(const std::string& camera_name) const;
|
const APIPCamera* getCamera(const std::string& camera_name) const;
|
||||||
|
@ -72,29 +72,29 @@ public: //Unreal specific methods
|
||||||
//parameters in NED frame
|
//parameters in NED frame
|
||||||
void setDebugPose(const Pose& debug_pose);
|
void setDebugPose(const Pose& debug_pose);
|
||||||
|
|
||||||
void setLogLine(std::string line);
|
|
||||||
|
|
||||||
FVector getUUPosition() const;
|
FVector getUUPosition() const;
|
||||||
FRotator getUUOrientation() const;
|
FRotator getUUOrientation() const;
|
||||||
|
|
||||||
const NedTransform& getNedTransform() const;
|
const NedTransform& getNedTransform() const;
|
||||||
|
|
||||||
void possess();
|
void possess();
|
||||||
void setupCamerasFromSettings();
|
|
||||||
|
|
||||||
void toggleTrace();
|
//allows setting ground truth from physics engine
|
||||||
|
void setGroundTruthKinematics(const msr::airlib::Kinematics::State* kinematics);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
UPROPERTY(VisibleAnywhere)
|
UPROPERTY(VisibleAnywhere)
|
||||||
UParticleSystem* collision_display_template;
|
UParticleSystem* collision_display_template;
|
||||||
|
|
||||||
//allows setting ground truth from physics engine
|
|
||||||
void setGroundTruthKinematics(const msr::airlib::Kinematics::State* kinematics);
|
|
||||||
|
|
||||||
private: //methods
|
private: //methods
|
||||||
bool canTeleportWhileMove() const;
|
bool canTeleportWhileMove() const;
|
||||||
void allowPassthroughToggleInput();
|
void allowPassthroughToggleInput();
|
||||||
void detectUsbRc();
|
void detectUsbRc();
|
||||||
|
void setupCamerasFromSettings(const std::map<std::string, APIPCamera*>& cameras);
|
||||||
|
void createCamerasFromSettings();
|
||||||
|
//on collision, pawns should update this
|
||||||
|
void onCollision(class UPrimitiveComponent* MyComp, class AActor* Other, class UPrimitiveComponent* OtherComp,
|
||||||
|
bool bSelfMoved, FVector HitLocation, FVector HitNormal, FVector NormalImpulse, const FHitResult& Hit);
|
||||||
|
|
||||||
//these methods are for future usage
|
//these methods are for future usage
|
||||||
void plot(std::istream& s, FColor color, const Vector3r& offset);
|
void plot(std::istream& s, FColor color, const Vector3r& offset);
|
||||||
|
@ -103,8 +103,11 @@ private: //methods
|
||||||
private: //vars
|
private: //vars
|
||||||
typedef msr::airlib::AirSimSettings AirSimSettings;
|
typedef msr::airlib::AirSimSettings AirSimSettings;
|
||||||
|
|
||||||
|
UPROPERTY() UClass* pip_camera_class_;
|
||||||
|
|
||||||
APawn* pawn_;
|
APawn* pawn_;
|
||||||
const std::map<std::string, APIPCamera*>* cameras_;
|
//TODO: should below be TMap to keep refs alive?
|
||||||
|
std::map<std::string, APIPCamera*> cameras_;
|
||||||
std::string vehicle_name_;
|
std::string vehicle_name_;
|
||||||
NedTransform ned_transform_;
|
NedTransform ned_transform_;
|
||||||
|
|
||||||
|
|
|
@ -80,8 +80,8 @@
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\car\SimModeCar.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\car\SimModeCar.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\ManualPoseController.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\ManualPoseController.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\MultiRotorConnector.cpp" />
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\Multirotor\MultirotorSimApi.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\SimModeWorldMultiRotor.cpp" />
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\Multirotor\SimModeWorldMultirotor.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\NedTransform.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\NedTransform.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\PIPCamera.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\PIPCamera.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\recording\RecordingFile.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\recording\RecordingFile.cpp" />
|
||||||
|
@ -93,9 +93,12 @@
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\simjoystick\SimJoyStick.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\simjoystick\SimJoyStick.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeBase.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeBase.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.cpp" />
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealImageCapture.cpp" />
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealDistanceSensor.cpp" />
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealSensorFactory.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehicleCameraConnector.cpp" />
|
<ClCompile Include="unreal\plugins\airsim\source\VehicleCameraConnector.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehicleConnectorBase.cpp" />
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\VehicleSimApi.cpp" />
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehiclePawnWrapper.cpp" />
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\WorldSimApi.cpp" />
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\AirBlueprintLib.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\AirBlueprintLib.h" />
|
||||||
|
@ -109,6 +112,7 @@
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\ManualPoseController.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\ManualPoseController.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\multirotor\MultiRotorConnector.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\multirotor\MultiRotorConnector.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\Multirotor\MultirotorSimApi.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\multirotor\SimModeWorldMultiRotor.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\multirotor\SimModeWorldMultiRotor.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\NedTransform.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\NedTransform.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\PIPCamera.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\PIPCamera.h" />
|
||||||
|
@ -121,8 +125,17 @@
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\simjoystick\SimJoyStick.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\simjoystick\SimJoyStick.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeBase.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeBase.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealImageCapture.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealDistanceSensor.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealSensorFactory.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\VehicleCameraConnector.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\VehicleCameraConnector.h" />
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\VehiclePawnWrapper.h" />
|
<ClInclude Include="unreal\plugins\airsim\source\VehiclePawnWrapper.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\VehicleSimApi.h" />
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\WorldSimApi.h" />
|
||||||
|
</ItemGroup>
|
||||||
|
<ItemGroup>
|
||||||
|
<None Include="Unreal\Plugins\AirSim\Source\AirSim.Build.4.15.cs" />
|
||||||
|
<None Include="Unreal\Plugins\AirSim\Source\AirSim.Build.cs" />
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
|
<Import Project="$(VCTargetsPath)\Microsoft.Cpp.targets" />
|
||||||
<ImportGroup Label="ExtensionTargets">
|
<ImportGroup Label="ExtensionTargets">
|
||||||
|
|
|
@ -42,12 +42,6 @@
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehicleCameraConnector.cpp">
|
<ClCompile Include="unreal\plugins\airsim\source\VehicleCameraConnector.cpp">
|
||||||
<Filter>Source Files</Filter>
|
<Filter>Source Files</Filter>
|
||||||
</ClCompile>
|
</ClCompile>
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehicleConnectorBase.cpp">
|
|
||||||
<Filter>Source Files</Filter>
|
|
||||||
</ClCompile>
|
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\VehiclePawnWrapper.cpp">
|
|
||||||
<Filter>Source Files</Filter>
|
|
||||||
</ClCompile>
|
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\car\CarPawn.cpp">
|
<ClCompile Include="unreal\plugins\airsim\source\car\CarPawn.cpp">
|
||||||
<Filter>Source Files</Filter>
|
<Filter>Source Files</Filter>
|
||||||
</ClCompile>
|
</ClCompile>
|
||||||
|
@ -63,12 +57,6 @@
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.cpp">
|
<ClCompile Include="unreal\plugins\airsim\source\multirotor\FlyingPawn.cpp">
|
||||||
<Filter>Source Files</Filter>
|
<Filter>Source Files</Filter>
|
||||||
</ClCompile>
|
</ClCompile>
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\MultiRotorConnector.cpp">
|
|
||||||
<Filter>Source Files</Filter>
|
|
||||||
</ClCompile>
|
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\multirotor\SimModeWorldMultiRotor.cpp">
|
|
||||||
<Filter>Source Files</Filter>
|
|
||||||
</ClCompile>
|
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\recording\RecordingFile.cpp">
|
<ClCompile Include="unreal\plugins\airsim\source\recording\RecordingFile.cpp">
|
||||||
<Filter>Source Files</Filter>
|
<Filter>Source Files</Filter>
|
||||||
</ClCompile>
|
</ClCompile>
|
||||||
|
@ -93,6 +81,27 @@
|
||||||
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.cpp">
|
<ClCompile Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.cpp">
|
||||||
<Filter>Source Files</Filter>
|
<Filter>Source Files</Filter>
|
||||||
</ClCompile>
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealImageCapture.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\VehicleSimApi.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\WorldSimApi.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealDistanceSensor.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealSensorFactory.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\Multirotor\MultirotorSimApi.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
|
<ClCompile Include="Unreal\Plugins\AirSim\Source\Multirotor\SimModeWorldMultirotor.cpp">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClCompile>
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\AirBlueprintLib.h">
|
<ClInclude Include="unreal\plugins\airsim\source\AirBlueprintLib.h">
|
||||||
|
@ -170,5 +179,31 @@
|
||||||
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.h">
|
<ClInclude Include="unreal\plugins\airsim\source\simmode\SimModeWorldBase.h">
|
||||||
<Filter>Header Files</Filter>
|
<Filter>Header Files</Filter>
|
||||||
</ClInclude>
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealImageCapture.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\VehicleSimApi.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\WorldSimApi.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealDistanceSensor.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\UnrealSensors\UnrealSensorFactory.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
<ClInclude Include="Unreal\Plugins\AirSim\Source\Multirotor\MultirotorSimApi.h">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</ClInclude>
|
||||||
|
</ItemGroup>
|
||||||
|
<ItemGroup>
|
||||||
|
<None Include="Unreal\Plugins\AirSim\Source\AirSim.Build.4.15.cs">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</None>
|
||||||
|
<None Include="Unreal\Plugins\AirSim\Source\AirSim.Build.cs">
|
||||||
|
<Filter>Source Files</Filter>
|
||||||
|
</None>
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
</Project>
|
</Project>
|
Загрузка…
Ссылка в новой задаче