Merge branch 'dev' of github.com:carla-simulator/carla into ruben/jenkins_migration
This commit is contained in:
commit
3930da297a
|
@ -1,6 +1,13 @@
|
||||||
## Latest Changes
|
## Latest Changes
|
||||||
* Prevent from segfault on failing SignalReference identification when loading OpenDrive files
|
* Prevent from segfault on failing SignalReference identification when loading OpenDrive files
|
||||||
* Added vehicle doors to the recorder
|
* Added vehicle doors to the recorder
|
||||||
|
* Added functions to get actor' components transform
|
||||||
|
* Added posibility to Digital Twins to work with local files (osm and xodr)
|
||||||
|
* Enable proper material merging for Building in Digital Twins
|
||||||
|
* Added functions to get actor' bones transforms
|
||||||
|
* Added functions to get actor' bones and components names
|
||||||
|
* Added functions to get actor' sockets transforms
|
||||||
|
* make PythonAPI Windows: Fixed incompatibility issue with Anaconda due `py` command.
|
||||||
|
|
||||||
## CARLA 0.9.15
|
## CARLA 0.9.15
|
||||||
|
|
||||||
|
|
|
@ -365,7 +365,7 @@ CARLA forum</a>
|
||||||
|
|
||||||
>In Windows it will be the default Python version for:
|
>In Windows it will be the default Python version for:
|
||||||
|
|
||||||
> py -3 --version
|
> python --version
|
||||||
|
|
||||||
>Make sure you are running your scripts with the version of Python that corresponds to your `.egg` file.
|
>Make sure you are running your scripts with the version of Python that corresponds to your `.egg` file.
|
||||||
>In Linux, you may also need to set your Python path to point to the CARLA `.egg`. To do this, run the following command:
|
>In Linux, you may also need to set your Python path to point to the CARLA `.egg`. To do this, run the following command:
|
||||||
|
|
|
@ -711,34 +711,39 @@ This raw [carla.Image](python_api.md#carla.Image) can be stored and converted it
|
||||||
raw_image.save_to_disk("path/to/save/converted/image",carla.ColorConverter.cityScapesPalette)
|
raw_image.save_to_disk("path/to/save/converted/image",carla.ColorConverter.cityScapesPalette)
|
||||||
```
|
```
|
||||||
|
|
||||||
The following tags are currently available:
|
The following tags are currently available (Note, tags changed from version 0.9.13 to 0.9.14):
|
||||||
|
|
||||||
| Value | Tag | Converted color | Description |
|
| Value | Tag | Converted color | Description |
|
||||||
| ----------------------------------- | ----------------------------------- | ----------------------------------- | ----------------------------------- |
|
| ----------------------------------- | ----------------------------------- | ----------------------------------- | ----------------------------------- |
|
||||||
| `0` | Unlabeled | `(0, 0, 0)` | Elements that have not been categorized are considered `Unlabeled`. This category is meant to be empty or at least contain elements with no collisions. |
|
| `0` | Unlabeled | `(0, 0, 0)` | Elements that have not been categorized are considered `Unlabeled`. This category is meant to be empty or at least contain elements with no collisions. |
|
||||||
| `1` | Building | `(70, 70, 70)` | Buildings like houses, skyscrapers,... and the elements attached to them. <br> E.g. air conditioners, scaffolding, awning or ladders and much more. |
|
| `1` | Roads | `(128, 64, 128)` | Part of ground on which cars usually drive. <br> E.g. lanes in any directions, and streets. |
|
||||||
| `2` | Fence | `(100, 40, 40)` | Barriers, railing, or other upright structures. Basically wood or wire assemblies that enclose an area of ground. |
|
| `2` | SideWalks | `(244, 35, 232)` | Part of ground designated for pedestrians or cyclists. Delimited from the road by some obstacle (such as curbs or poles), not only by markings. This label includes a possibly delimiting curb, traffic islands (the walkable part), and pedestrian zones. |
|
||||||
| `3` | Other | `(55, 90, 80)` | Everything that does not belong to any other category. |
|
| `3` | Building | `(70, 70, 70)` | Buildings like houses, skyscrapers,... and the elements attached to them. <br> E.g. air conditioners, scaffolding, awning or ladders and much more. |
|
||||||
| `4` | Pedestrian | `(220, 20, 60)` | Humans that walk or ride/drive any kind of vehicle or mobility system. <br> E.g. bicycles or scooters, skateboards, horses, roller-blades, wheel-chairs, etc. |
|
| `4` | Wall | `(102, 102, 156)` | Individual standing walls. Not part of a building. |
|
||||||
| `5` | Pole | `(153, 153, 153)` | Small mainly vertically oriented pole. If the pole has a horizontal part (often for traffic light poles) this is also considered pole. <br> E.g. sign pole, traffic light poles. |
|
| `5` | Fence | `(190, 153, 153)` | Barriers, railing, or other upright structures. Basically wood or wire assemblies that enclose an area of ground. |
|
||||||
| `6` | RoadLine | `(157, 234, 50)` | The markings on the road. |
|
| `6` | Pole | `(153, 153, 153)` | Small mainly vertically oriented pole. If the pole has a horizontal part (often for traffic light poles) this is also considered pole. <br> E.g. sign pole, traffic light poles. |
|
||||||
| `7` | Road | `(128, 64, 128)` | Part of ground on which cars usually drive. <br> E.g. lanes in any directions, and streets. |
|
| `7` | TrafficLight | `(250, 170, 30)` | Traffic light boxes without their poles. |
|
||||||
| `8` | SideWalk | `(244, 35, 232)` | Part of ground designated for pedestrians or cyclists. Delimited from the road by some obstacle (such as curbs or poles), not only by markings. This label includes a possibly delimiting curb, traffic islands (the walkable part), and pedestrian zones. |
|
| `8` | TrafficSign | `(220, 220, 0)` | Signs installed by the state/city authority, usually for traffic regulation. This category does not include the poles where signs are attached to. <br> E.g. traffic- signs, parking signs, direction signs... |
|
||||||
| `9` | Vegetation | `(107, 142, 35)` | Trees, hedges, all kinds of vertical vegetation. Ground-level vegetation is considered `Terrain`. |
|
| `9` | Vegetation | `(107, 142, 35)` | Trees, hedges, all kinds of vertical vegetation. Ground-level vegetation is considered `Terrain`. |
|
||||||
| `10` | Vehicles | `(0, 0, 142)` | Cars, vans, trucks, motorcycles, bikes, buses, trains. |
|
| `10` | Terrain | `(152, 251, 152)` | Grass, ground-level vegetation, soil or sand. These areas are not meant to be driven on. This label includes a possibly delimiting curb. |
|
||||||
| `11` | Wall | `(102, 102, 156)` | Individual standing walls. Not part of a building. |
|
| `11` | Sky | `(70, 130, 180)` | Open sky. Includes clouds and the sun. |
|
||||||
| `12` | TrafficSign | `(220, 220, 0)` | Signs installed by the state/city authority, usually for traffic regulation. This category does not include the poles where signs are attached to. <br> E.g. traffic- signs, parking signs, direction signs... |
|
| `12` | Pedestrian | `(220, 20, 60)` | Humans that walk |
|
||||||
| `13` | Sky | `(70, 130, 180)` | Open sky. Includes clouds and the sun. |
|
| `13` | Rider | `(255, 0, 0)` | Humans that ride/drive any kind of vehicle or mobility system <br> E.g. bicycles or scooters, skateboards, horses, roller-blades, wheel-chairs, etc. . |
|
||||||
| `14` | Ground | `(81, 0, 81)` | Any horizontal ground-level structures that does not match any other category. For example areas shared by vehicles and pedestrians, or flat roundabouts delimited from the road by a curb. |
|
| `14` | Car | `(0, 0, 142)` | Cars, vans |
|
||||||
| `15` | Bridge | `(150, 100, 100)` | Only the structure of the bridge. Fences, people, vehicles, an other elements on top of it are labeled separately. |
|
| `15` | Truck | `(0, 0, 70)` | Trucks |
|
||||||
| `16` | RailTrack | `(230, 150, 140)` | All kind of rail tracks that are non-drivable by cars. <br> E.g. subway and train rail tracks. |
|
| `16` | Bus | `(0, 60, 100)` | Busses |
|
||||||
| `17` | GuardRail | `(180, 165, 180)` | All types of guard rails/crash barriers. |
|
| `17` | Train | `(0, 60, 100)` | Trains |
|
||||||
| `18` | TrafficLight | `(250, 170, 30)` | Traffic light boxes without their poles. |
|
| `18` | Motorcycle | `(0, 0, 230)` | Motorcycle, Motorbike |
|
||||||
| `19` | Static | `(110, 190, 160)` | Elements in the scene and props that are immovable. <br> E.g. fire hydrants, fixed benches, fountains, bus stops, etc. |
|
| `19` | Bicycle | `(119, 11, 32)` | Bicylces |
|
||||||
| `20` | Dynamic | `(170, 120, 50)` | Elements whose position is susceptible to change over time. <br> E.g. Movable trash bins, buggies, bags, wheelchairs, animals, etc. |
|
| `20` | Static | `(110, 190, 160)` | Elements in the scene and props that are immovable. <br> E.g. fire hydrants, fixed benches, fountains, bus stops, etc. |
|
||||||
| `21` | Water | `(45, 60, 150)` | Horizontal water surfaces. <br> E.g. Lakes, sea, rivers. |
|
| `21` | Dynamic | `(170, 120, 50)` | Elements whose position is susceptible to change over time. <br> E.g. Movable trash bins, buggies, bags, wheelchairs, animals, etc. |
|
||||||
| `22` | Terrain | `(145, 170, 100)` | Grass, ground-level vegetation, soil or sand. These areas are not meant to be driven on. This label includes a possibly delimiting curb. |
|
| `22` | Other | `(55, 90, 80)` | Everything that does not belong to any other category. |
|
||||||
|
| `23` | Water | `(45, 60, 150)` | Horizontal water surfaces. <br> E.g. Lakes, sea, rivers. |
|
||||||
|
| `24` | RoadLine | `(157, 234, 50)` | The markings on the road. |
|
||||||
|
| `25` | Ground | `(81, 0, 81)` | Any horizontal ground-level structures that does not match any other category. For example areas shared by vehicles and pedestrians, or flat roundabouts delimited from the road by a curb. |
|
||||||
|
| `26` | Bridge | `(150, 100, 100)` | Only the structure of the bridge. Fences, people, vehicles, an other elements on top of it are labeled separately. |
|
||||||
|
| `27` | RailTrack | `(230, 150, 140)` | All kind of rail tracks that are non-drivable by cars. <br> E.g. subway and train rail tracks. |
|
||||||
|
| `28` | GuardRail | `(180, 165, 180)` | All types of guard rails/crash barriers. |
|
||||||
<br>
|
<br>
|
||||||
|
|
||||||
!!! Note
|
!!! Note
|
||||||
|
|
|
@ -22,6 +22,9 @@ In this tutorial we will cover the process of creating a simple map for use with
|
||||||
* [Next steps](#next-steps)
|
* [Next steps](#next-steps)
|
||||||
* __[Trees and vegetation](#trees-and-vegetation)__
|
* __[Trees and vegetation](#trees-and-vegetation)__
|
||||||
* [Foliage tool](#foliage-tool)
|
* [Foliage tool](#foliage-tool)
|
||||||
|
* __[Exporting a map](#exporting-a-map)__
|
||||||
|
* [Exporting a map as a separate package](#exporting-a-map-as-a-separate-package)
|
||||||
|
* [Exporting a map as part of a complete CARLA package](#exporting-a-map-as-part-of-a-complete-carla-package)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -409,6 +412,50 @@ Drag your desired foliage item into the box labeled `+ Drop Foliage Here`. Set a
|
||||||
|
|
||||||
![foliage_paint](img/tuto_content_authoring_maps/foliage_paint.gif)
|
![foliage_paint](img/tuto_content_authoring_maps/foliage_paint.gif)
|
||||||
|
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## Exporting a map
|
||||||
|
|
||||||
|
### Exporting a map as a separate package
|
||||||
|
|
||||||
|
To export a map as a map package that can be ingested into a standalone CARLA package installation, use the `make package` command as follows:
|
||||||
|
|
||||||
|
```sh
|
||||||
|
make package ARGS="--packages=<mapName>"
|
||||||
|
```
|
||||||
|
|
||||||
|
The `<mapName>` must point to a json file located in `CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Config` named *mapName.Package.json* which has the following structure:
|
||||||
|
|
||||||
|
```json
|
||||||
|
{
|
||||||
|
"maps": [
|
||||||
|
{
|
||||||
|
"path": "/Game/Carla/Maps/",
|
||||||
|
"name": "MyMap",
|
||||||
|
"use_carla_materials": true
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"props": []
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Your map should have been saved as `MyMap.umap` file in the `CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Maps` directory.
|
||||||
|
|
||||||
|
The exported map archive will be saved in the `Dist` folder on Linux and the `/Build/UE4Carla/` folder on Windows.
|
||||||
|
|
||||||
|
### Exporting a map as part of a complete CARLA package
|
||||||
|
|
||||||
|
To export the map as part of a complete CARLA package, such that the map is available on launch of the package, include the following line in the `DefaultGame.ini` file in `CARLA_ROOT/Unreal/CarlaUE4/Config/`:
|
||||||
|
|
||||||
|
```
|
||||||
|
+MapsToCook=(FilePath="/Game/Carla/Maps/MyMap")
|
||||||
|
```
|
||||||
|
|
||||||
|
This line should be added in the `[/Script/UnrealEd.ProjectPackagingSettings]` section, preferably next to the other `MapsToCook(...)` entries. Then run `make package` command to build a package containing your map. The exported CARLA package with your map will be saved in the `Dist` folder on Linux and the `/Build/UE4Carla/` folder on Windows.
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
## Next steps
|
## Next steps
|
||||||
|
|
||||||
Continue customizing your map using the tools and guides below:
|
Continue customizing your map using the tools and guides below:
|
||||||
|
|
|
@ -32,6 +32,38 @@ namespace client {
|
||||||
return GetEpisode().Lock()->GetActorAcceleration(*this);
|
return GetEpisode().Lock()->GetActorAcceleration(*this);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
geom::Transform Actor::GetComponentWorldTransform(const std::string componentName) const {
|
||||||
|
return GetEpisode().Lock()->GetActorComponentWorldTransform(*this, componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
geom::Transform Actor::GetComponentRelativeTransform(const std::string componentName) const {
|
||||||
|
return GetEpisode().Lock()->GetActorComponentRelativeTransform(*this, componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Actor::GetBoneWorldTransforms() const {
|
||||||
|
return GetEpisode().Lock()->GetActorBoneWorldTransforms(*this);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Actor::GetBoneRelativeTransforms() const {
|
||||||
|
return GetEpisode().Lock()->GetActorBoneRelativeTransforms(*this);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> Actor::GetComponentNames() const {
|
||||||
|
return GetEpisode().Lock()->GetActorComponentNames(*this);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> Actor::GetBoneNames() const {
|
||||||
|
return GetEpisode().Lock()->GetActorBoneNames(*this);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Actor::GetSocketWorldTransforms() const {
|
||||||
|
return GetEpisode().Lock()->GetActorSocketWorldTransforms(*this);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Actor::GetSocketRelativeTransforms() const {
|
||||||
|
return GetEpisode().Lock()->GetActorSocketRelativeTransforms(*this);
|
||||||
|
}
|
||||||
|
|
||||||
void Actor::SetLocation(const geom::Location &location) {
|
void Actor::SetLocation(const geom::Location &location) {
|
||||||
GetEpisode().Lock()->SetActorLocation(*this, location);
|
GetEpisode().Lock()->SetActorLocation(*this, location);
|
||||||
}
|
}
|
||||||
|
|
|
@ -60,6 +60,22 @@ namespace client {
|
||||||
/// acceleration calculated after the actor's velocity.
|
/// acceleration calculated after the actor's velocity.
|
||||||
geom::Vector3D GetAcceleration() const;
|
geom::Vector3D GetAcceleration() const;
|
||||||
|
|
||||||
|
geom::Transform GetComponentWorldTransform(const std::string componentName) const;
|
||||||
|
|
||||||
|
geom::Transform GetComponentRelativeTransform(const std::string componentName) const;
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetBoneWorldTransforms() const;
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetBoneRelativeTransforms() const;
|
||||||
|
|
||||||
|
std::vector<std::string> GetComponentNames() const;
|
||||||
|
|
||||||
|
std::vector<std::string> GetBoneNames() const;
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetSocketWorldTransforms() const;
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetSocketRelativeTransforms() const;
|
||||||
|
|
||||||
/// Teleport the actor to @a location.
|
/// Teleport the actor to @a location.
|
||||||
void SetLocation(const geom::Location &location);
|
void SetLocation(const geom::Location &location);
|
||||||
|
|
||||||
|
|
|
@ -119,17 +119,19 @@ namespace client {
|
||||||
const ActorBlueprint &blueprint,
|
const ActorBlueprint &blueprint,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent_actor,
|
Actor *parent_actor,
|
||||||
rpc::AttachmentType attachment_type) {
|
rpc::AttachmentType attachment_type,
|
||||||
return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor, attachment_type);
|
const std::string& socket_name) {
|
||||||
|
return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor, attachment_type, GarbageCollectionPolicy::Inherit, socket_name);
|
||||||
}
|
}
|
||||||
|
|
||||||
SharedPtr<Actor> World::TrySpawnActor(
|
SharedPtr<Actor> World::TrySpawnActor(
|
||||||
const ActorBlueprint &blueprint,
|
const ActorBlueprint &blueprint,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent_actor,
|
Actor *parent_actor,
|
||||||
rpc::AttachmentType attachment_type) noexcept {
|
rpc::AttachmentType attachment_type,
|
||||||
|
const std::string& socket_name) noexcept {
|
||||||
try {
|
try {
|
||||||
return SpawnActor(blueprint, transform, parent_actor, attachment_type);
|
return SpawnActor(blueprint, transform, parent_actor, attachment_type, socket_name);
|
||||||
} catch (const std::exception &) {
|
} catch (const std::exception &) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
#include "carla/rpc/Texture.h"
|
#include "carla/rpc/Texture.h"
|
||||||
#include "carla/rpc/MaterialParameter.h"
|
#include "carla/rpc/MaterialParameter.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
#include <boost/optional.hpp>
|
#include <boost/optional.hpp>
|
||||||
|
|
||||||
namespace carla {
|
namespace carla {
|
||||||
|
@ -112,7 +113,8 @@ namespace client {
|
||||||
const ActorBlueprint &blueprint,
|
const ActorBlueprint &blueprint,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent = nullptr,
|
Actor *parent = nullptr,
|
||||||
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid);
|
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid,
|
||||||
|
const std::string& socket_name = "");
|
||||||
|
|
||||||
/// Same as SpawnActor but return nullptr on failure instead of throwing an
|
/// Same as SpawnActor but return nullptr on failure instead of throwing an
|
||||||
/// exception.
|
/// exception.
|
||||||
|
@ -120,7 +122,8 @@ namespace client {
|
||||||
const ActorBlueprint &blueprint,
|
const ActorBlueprint &blueprint,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent = nullptr,
|
Actor *parent = nullptr,
|
||||||
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid) noexcept;
|
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid,
|
||||||
|
const std::string& socket_name = "") noexcept;
|
||||||
|
|
||||||
/// Block calling thread until a world tick is received.
|
/// Block calling thread until a world tick is received.
|
||||||
WorldSnapshot WaitForTick(time_duration timeout) const;
|
WorldSnapshot WaitForTick(time_duration timeout) const;
|
||||||
|
|
|
@ -330,7 +330,8 @@ namespace detail {
|
||||||
const rpc::ActorDescription &description,
|
const rpc::ActorDescription &description,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
rpc::ActorId parent,
|
rpc::ActorId parent,
|
||||||
rpc::AttachmentType attachment_type) {
|
rpc::AttachmentType attachment_type,
|
||||||
|
const std::string& socket_name) {
|
||||||
|
|
||||||
if (attachment_type == rpc::AttachmentType::SpringArm ||
|
if (attachment_type == rpc::AttachmentType::SpringArm ||
|
||||||
attachment_type == rpc::AttachmentType::SpringArmGhost)
|
attachment_type == rpc::AttachmentType::SpringArmGhost)
|
||||||
|
@ -348,7 +349,8 @@ namespace detail {
|
||||||
description,
|
description,
|
||||||
transform,
|
transform,
|
||||||
parent,
|
parent,
|
||||||
attachment_type);
|
attachment_type,
|
||||||
|
socket_name);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Client::DestroyActor(rpc::ActorId actor) {
|
bool Client::DestroyActor(rpc::ActorId actor) {
|
||||||
|
@ -408,6 +410,44 @@ namespace detail {
|
||||||
_pimpl->AsyncCall("add_actor_torque", actor, vector);
|
_pimpl->AsyncCall("add_actor_torque", actor, vector);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
geom::Transform Client::GetActorComponentWorldTransform(rpc::ActorId actor, const std::string componentName) {
|
||||||
|
return _pimpl->CallAndWait<geom::Transform>("get_actor_component_world_transform", actor, componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
geom::Transform Client::GetActorComponentRelativeTransform(rpc::ActorId actor, const std::string componentName) {
|
||||||
|
return _pimpl->CallAndWait<geom::Transform>("get_actor_component_relative_transform", actor, componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Client::GetActorBoneWorldTransforms(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<geom::Transform>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_bone_world_transforms", actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Client::GetActorBoneRelativeTransforms(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<geom::Transform>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_bone_relative_transforms", actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> Client::GetActorComponentNames(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<std::string>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_component_names", actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> Client::GetActorBoneNames(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<std::string>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_bone_names", actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Client::GetActorSocketWorldTransforms(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<geom::Transform>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_socket_world_transforms", actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> Client::GetActorSocketRelativeTransforms(rpc::ActorId actor) {
|
||||||
|
using return_t = std::vector<geom::Transform>;
|
||||||
|
return _pimpl->CallAndWait<return_t>("get_actor_socket_relative_transforms", actor);
|
||||||
|
}
|
||||||
|
|
||||||
void Client::SetActorSimulatePhysics(rpc::ActorId actor, const bool enabled) {
|
void Client::SetActorSimulatePhysics(rpc::ActorId actor, const bool enabled) {
|
||||||
_pimpl->CallAndWait<void>("set_actor_simulate_physics", actor, enabled);
|
_pimpl->CallAndWait<void>("set_actor_simulate_physics", actor, enabled);
|
||||||
}
|
}
|
||||||
|
|
|
@ -179,7 +179,8 @@ namespace detail {
|
||||||
const rpc::ActorDescription &description,
|
const rpc::ActorDescription &description,
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
rpc::ActorId parent,
|
rpc::ActorId parent,
|
||||||
rpc::AttachmentType attachment_type);
|
rpc::AttachmentType attachment_type,
|
||||||
|
const std::string& socket_name = "");
|
||||||
|
|
||||||
bool DestroyActor(rpc::ActorId actor);
|
bool DestroyActor(rpc::ActorId actor);
|
||||||
|
|
||||||
|
@ -232,6 +233,32 @@ namespace detail {
|
||||||
rpc::ActorId actor,
|
rpc::ActorId actor,
|
||||||
const geom::Vector3D &vector);
|
const geom::Vector3D &vector);
|
||||||
|
|
||||||
|
geom::Transform GetActorComponentWorldTransform(
|
||||||
|
rpc::ActorId actor,
|
||||||
|
const std::string componentName);
|
||||||
|
|
||||||
|
geom::Transform GetActorComponentRelativeTransform(
|
||||||
|
rpc::ActorId actor,
|
||||||
|
const std::string componentName);
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorBoneWorldTransforms(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorBoneRelativeTransforms(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
|
std::vector<std::string> GetActorComponentNames(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
|
std::vector<std::string> GetActorBoneNames(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorSocketWorldTransforms(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorSocketRelativeTransforms(
|
||||||
|
rpc::ActorId actor);
|
||||||
|
|
||||||
void SetActorSimulatePhysics(
|
void SetActorSimulatePhysics(
|
||||||
rpc::ActorId actor,
|
rpc::ActorId actor,
|
||||||
bool enabled);
|
bool enabled);
|
||||||
|
|
|
@ -347,14 +347,16 @@ EpisodeProxy Simulator::GetCurrentEpisode() {
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent,
|
Actor *parent,
|
||||||
rpc::AttachmentType attachment_type,
|
rpc::AttachmentType attachment_type,
|
||||||
GarbageCollectionPolicy gc) {
|
GarbageCollectionPolicy gc,
|
||||||
|
const std::string& socket_name) {
|
||||||
rpc::Actor actor;
|
rpc::Actor actor;
|
||||||
if (parent != nullptr) {
|
if (parent != nullptr) {
|
||||||
actor = _client.SpawnActorWithParent(
|
actor = _client.SpawnActorWithParent(
|
||||||
blueprint.MakeActorDescription(),
|
blueprint.MakeActorDescription(),
|
||||||
transform,
|
transform,
|
||||||
parent->GetId(),
|
parent->GetId(),
|
||||||
attachment_type);
|
attachment_type,
|
||||||
|
socket_name);
|
||||||
} else {
|
} else {
|
||||||
actor = _client.SpawnActor(
|
actor = _client.SpawnActor(
|
||||||
blueprint.MakeActorDescription(),
|
blueprint.MakeActorDescription(),
|
||||||
|
|
|
@ -357,7 +357,8 @@ namespace detail {
|
||||||
const geom::Transform &transform,
|
const geom::Transform &transform,
|
||||||
Actor *parent = nullptr,
|
Actor *parent = nullptr,
|
||||||
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid,
|
rpc::AttachmentType attachment_type = rpc::AttachmentType::Rigid,
|
||||||
GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit);
|
GarbageCollectionPolicy gc = GarbageCollectionPolicy::Inherit,
|
||||||
|
const std::string& socket_name = "");
|
||||||
|
|
||||||
bool DestroyActor(Actor &actor);
|
bool DestroyActor(Actor &actor);
|
||||||
|
|
||||||
|
@ -438,6 +439,38 @@ namespace detail {
|
||||||
return GetActorSnapshot(actor).acceleration;
|
return GetActorSnapshot(actor).acceleration;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
geom::Transform GetActorComponentWorldTransform(const Actor &actor, const std::string componentName) {
|
||||||
|
return _client.GetActorComponentWorldTransform(actor.GetId(), componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
geom::Transform GetActorComponentRelativeTransform(const Actor &actor, std::string componentName) {
|
||||||
|
return _client.GetActorComponentRelativeTransform(actor.GetId(), componentName);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorBoneWorldTransforms(const Actor &actor) {
|
||||||
|
return _client.GetActorBoneWorldTransforms(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorBoneRelativeTransforms(const Actor &actor) {
|
||||||
|
return _client.GetActorBoneRelativeTransforms(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> GetActorComponentNames(const Actor &actor) {
|
||||||
|
return _client.GetActorComponentNames(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<std::string> GetActorBoneNames(const Actor &actor) {
|
||||||
|
return _client.GetActorBoneNames(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorSocketWorldTransforms(const Actor &actor) {
|
||||||
|
return _client.GetActorSocketWorldTransforms(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<geom::Transform> GetActorSocketRelativeTransforms(const Actor &actor) {
|
||||||
|
return _client.GetActorSocketRelativeTransforms(actor.GetId());
|
||||||
|
}
|
||||||
|
|
||||||
void SetActorLocation(Actor &actor, const geom::Location &location) {
|
void SetActorLocation(Actor &actor, const geom::Location &location) {
|
||||||
_client.SetActorLocation(actor.GetId(), location);
|
_client.SetActorLocation(actor.GetId(), location);
|
||||||
}
|
}
|
||||||
|
|
|
@ -1238,7 +1238,11 @@ namespace road {
|
||||||
geom::Transform lanetransform = lane->ComputeTransform(s_current);
|
geom::Transform lanetransform = lane->ComputeTransform(s_current);
|
||||||
geom::Transform treeTransform(treeposition, lanetransform.rotation);
|
geom::Transform treeTransform(treeposition, lanetransform.rotation);
|
||||||
const carla::road::element::RoadInfoSpeed* roadinfo = lane->GetInfo<carla::road::element::RoadInfoSpeed>(s_current);
|
const carla::road::element::RoadInfoSpeed* roadinfo = lane->GetInfo<carla::road::element::RoadInfoSpeed>(s_current);
|
||||||
|
if(roadinfo){
|
||||||
transforms.push_back(std::make_pair(treeTransform, roadinfo->GetType()));
|
transforms.push_back(std::make_pair(treeTransform, roadinfo->GetType()));
|
||||||
|
}else{
|
||||||
|
transforms.push_back(std::make_pair(treeTransform, "urban"));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
s_current += distancebetweentrees;
|
s_current += distancebetweentrees;
|
||||||
}
|
}
|
||||||
|
|
|
@ -10,6 +10,7 @@
|
||||||
#include "carla/MsgPackAdaptors.h"
|
#include "carla/MsgPackAdaptors.h"
|
||||||
#include "carla/geom/Transform.h"
|
#include "carla/geom/Transform.h"
|
||||||
#include "carla/rpc/ActorDescription.h"
|
#include "carla/rpc/ActorDescription.h"
|
||||||
|
#include "carla/rpc/AttachmentType.h"
|
||||||
#include "carla/rpc/ActorId.h"
|
#include "carla/rpc/ActorId.h"
|
||||||
#include "carla/rpc/TrafficLightState.h"
|
#include "carla/rpc/TrafficLightState.h"
|
||||||
#include "carla/rpc/VehicleAckermannControl.h"
|
#include "carla/rpc/VehicleAckermannControl.h"
|
||||||
|
@ -18,6 +19,8 @@
|
||||||
#include "carla/rpc/VehicleLightState.h"
|
#include "carla/rpc/VehicleLightState.h"
|
||||||
#include "carla/rpc/WalkerControl.h"
|
#include "carla/rpc/WalkerControl.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
#ifdef _MSC_VER
|
#ifdef _MSC_VER
|
||||||
#pragma warning(push)
|
#pragma warning(push)
|
||||||
#pragma warning(disable:4583)
|
#pragma warning(disable:4583)
|
||||||
|
@ -59,11 +62,19 @@ namespace rpc {
|
||||||
: description(std::move(description)),
|
: description(std::move(description)),
|
||||||
transform(transform),
|
transform(transform),
|
||||||
parent(parent) {}
|
parent(parent) {}
|
||||||
|
SpawnActor(ActorDescription description, const geom::Transform &transform, ActorId parent, AttachmentType attachment_type, const std::string& bone)
|
||||||
|
: description(std::move(description)),
|
||||||
|
transform(transform),
|
||||||
|
parent(parent),
|
||||||
|
attachment_type(attachment_type),
|
||||||
|
socket_name(bone) {}
|
||||||
ActorDescription description;
|
ActorDescription description;
|
||||||
geom::Transform transform;
|
geom::Transform transform;
|
||||||
boost::optional<ActorId> parent;
|
boost::optional<ActorId> parent;
|
||||||
|
AttachmentType attachment_type;
|
||||||
|
std::string socket_name;
|
||||||
std::vector<Command> do_after;
|
std::vector<Command> do_after;
|
||||||
MSGPACK_DEFINE_ARRAY(description, transform, parent, do_after);
|
MSGPACK_DEFINE_ARRAY(description, transform, parent, attachment_type, socket_name, do_after);
|
||||||
};
|
};
|
||||||
|
|
||||||
struct DestroyActor : CommandBase<DestroyActor> {
|
struct DestroyActor : CommandBase<DestroyActor> {
|
||||||
|
|
|
@ -113,6 +113,14 @@ void export_actor() {
|
||||||
.def("get_velocity", &cc::Actor::GetVelocity)
|
.def("get_velocity", &cc::Actor::GetVelocity)
|
||||||
.def("get_angular_velocity", &cc::Actor::GetAngularVelocity)
|
.def("get_angular_velocity", &cc::Actor::GetAngularVelocity)
|
||||||
.def("get_acceleration", &cc::Actor::GetAcceleration)
|
.def("get_acceleration", &cc::Actor::GetAcceleration)
|
||||||
|
.def("get_component_world_transform", &cc::Actor::GetComponentWorldTransform, (arg("component_name")))
|
||||||
|
.def("get_component_relative_transform", &cc::Actor::GetComponentRelativeTransform, (arg("component_name")))
|
||||||
|
.def("get_bone_world_transforms", CALL_RETURNING_LIST(cc::Actor,GetBoneWorldTransforms))
|
||||||
|
.def("get_bone_relative_transforms", CALL_RETURNING_LIST(cc::Actor,GetBoneRelativeTransforms))
|
||||||
|
.def("get_component_names", CALL_RETURNING_LIST(cc::Actor,GetComponentNames))
|
||||||
|
.def("get_bone_names", CALL_RETURNING_LIST(cc::Actor,GetBoneNames))
|
||||||
|
.def("get_socket_world_transforms", CALL_RETURNING_LIST(cc::Actor,GetSocketWorldTransforms))
|
||||||
|
.def("get_socket_relative_transforms", CALL_RETURNING_LIST(cc::Actor,GetSocketRelativeTransforms))
|
||||||
.def("set_location", &cc::Actor::SetLocation, (arg("location")))
|
.def("set_location", &cc::Actor::SetLocation, (arg("location")))
|
||||||
.def("set_transform", &cc::Actor::SetTransform, (arg("transform")))
|
.def("set_transform", &cc::Actor::SetTransform, (arg("transform")))
|
||||||
.def("set_target_velocity", &cc::Actor::SetTargetVelocity, (arg("velocity")))
|
.def("set_target_velocity", &cc::Actor::SetTargetVelocity, (arg("velocity")))
|
||||||
|
|
|
@ -82,9 +82,15 @@ void export_commands() {
|
||||||
"__init__",
|
"__init__",
|
||||||
&command_impl::CustomSpawnActorInit<cc::ActorBlueprint, cg::Transform, ActorPtr>,
|
&command_impl::CustomSpawnActorInit<cc::ActorBlueprint, cg::Transform, ActorPtr>,
|
||||||
(arg("blueprint"), arg("transform"), arg("parent")))
|
(arg("blueprint"), arg("transform"), arg("parent")))
|
||||||
|
.def(
|
||||||
|
"__init__",
|
||||||
|
&command_impl::CustomSpawnActorInit<cc::ActorBlueprint, cg::Transform, ActorPtr, cr::AttachmentType, std::string>,
|
||||||
|
(arg("blueprint"), arg("transform"), arg("parent"), arg("attachment_type"), arg("socket_name")))
|
||||||
.def(init<cr::Command::SpawnActor>())
|
.def(init<cr::Command::SpawnActor>())
|
||||||
.def_readwrite("transform", &cr::Command::SpawnActor::transform)
|
.def_readwrite("transform", &cr::Command::SpawnActor::transform)
|
||||||
.def_readwrite("parent_id", &cr::Command::SpawnActor::parent)
|
.def_readwrite("parent_id", &cr::Command::SpawnActor::parent)
|
||||||
|
.def_readwrite("attachment_type", &cr::Command::SpawnActor::attachment_type)
|
||||||
|
.def_readwrite("socket_name", &cr::Command::SpawnActor::socket_name)
|
||||||
.def("then", &command_impl::Then, (arg("command")))
|
.def("then", &command_impl::Then, (arg("command")))
|
||||||
;
|
;
|
||||||
|
|
||||||
|
|
|
@ -11,6 +11,8 @@
|
||||||
#include <carla/rpc/EnvironmentObject.h>
|
#include <carla/rpc/EnvironmentObject.h>
|
||||||
#include <carla/rpc/ObjectLabel.h>
|
#include <carla/rpc/ObjectLabel.h>
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>
|
#include <boost/python/suite/indexing/vector_indexing_suite.hpp>
|
||||||
|
|
||||||
namespace carla {
|
namespace carla {
|
||||||
|
@ -293,15 +295,17 @@ void export_world() {
|
||||||
const cc::ActorBlueprint &blueprint, \
|
const cc::ActorBlueprint &blueprint, \
|
||||||
const cg::Transform &transform, \
|
const cg::Transform &transform, \
|
||||||
cc::Actor *parent, \
|
cc::Actor *parent, \
|
||||||
cr::AttachmentType attachment_type) { \
|
cr::AttachmentType attachment_type, \
|
||||||
|
const std::string& bone) { \
|
||||||
carla::PythonUtil::ReleaseGIL unlock; \
|
carla::PythonUtil::ReleaseGIL unlock; \
|
||||||
return self.fn(blueprint, transform, parent, attachment_type); \
|
return self.fn(blueprint, transform, parent, attachment_type, bone); \
|
||||||
}, \
|
}, \
|
||||||
( \
|
( \
|
||||||
arg("blueprint"), \
|
arg("blueprint"), \
|
||||||
arg("transform"), \
|
arg("transform"), \
|
||||||
arg("attach_to")=carla::SharedPtr<cc::Actor>(), \
|
arg("attach_to")=carla::SharedPtr<cc::Actor>(), \
|
||||||
arg("attachment_type")=cr::AttachmentType::Rigid)
|
arg("attachment_type")=cr::AttachmentType::Rigid, \
|
||||||
|
arg("bone")=std::string())
|
||||||
|
|
||||||
class_<cc::World>("World", no_init)
|
class_<cc::World>("World", no_init)
|
||||||
.add_property("id", &cc::World::GetId)
|
.add_property("id", &cc::World::GetId)
|
||||||
|
|
|
@ -0,0 +1,34 @@
|
||||||
|
import glob
|
||||||
|
import os
|
||||||
|
import sys
|
||||||
|
|
||||||
|
try:
|
||||||
|
sys.path.append(glob.glob('../carla/dist/carla-*%d.%d-%s.egg' % (
|
||||||
|
sys.version_info.major,
|
||||||
|
sys.version_info.minor,
|
||||||
|
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||||
|
except IndexError:
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
# ==============================================================================
|
||||||
|
# -- imports -------------------------------------------------------------------
|
||||||
|
# ==============================================================================
|
||||||
|
|
||||||
|
|
||||||
|
import carla
|
||||||
|
|
||||||
|
client = carla.Client('localhost', 2000)
|
||||||
|
world = client.get_world()
|
||||||
|
|
||||||
|
location = carla.Location(200.0, 200.0, 200.0)
|
||||||
|
rotation = carla.Rotation(0.0, 0.0, 0.0)
|
||||||
|
transform = carla.Transform(location, rotation)
|
||||||
|
|
||||||
|
bp_library = world.get_blueprint_library()
|
||||||
|
bp_audi = bp_library.find('vehicle.audi.tt')
|
||||||
|
audi = world.spawn_actor(bp_audi, transform)
|
||||||
|
|
||||||
|
component_transform = audi.get_component_world_transform('front-blinker-r-1')
|
||||||
|
print(component_transform)
|
||||||
|
|
|
@ -294,11 +294,12 @@ carla::rpc::Actor UCarlaEpisode::SerializeActor(AActor* Actor) const
|
||||||
void UCarlaEpisode::AttachActors(
|
void UCarlaEpisode::AttachActors(
|
||||||
AActor *Child,
|
AActor *Child,
|
||||||
AActor *Parent,
|
AActor *Parent,
|
||||||
EAttachmentType InAttachmentType)
|
EAttachmentType InAttachmentType,
|
||||||
|
const FString& SocketName)
|
||||||
{
|
{
|
||||||
Child->AddActorWorldOffset(FVector(CurrentMapOrigin));
|
Child->AddActorWorldOffset(FVector(CurrentMapOrigin));
|
||||||
|
|
||||||
UActorAttacher::AttachActors(Child, Parent, InAttachmentType);
|
UActorAttacher::AttachActors(Child, Parent, InAttachmentType, SocketName);
|
||||||
|
|
||||||
if (bIsPrimaryServer)
|
if (bIsPrimaryServer)
|
||||||
{
|
{
|
||||||
|
|
|
@ -245,7 +245,8 @@ public:
|
||||||
void AttachActors(
|
void AttachActors(
|
||||||
AActor *Child,
|
AActor *Child,
|
||||||
AActor *Parent,
|
AActor *Parent,
|
||||||
EAttachmentType InAttachmentType = EAttachmentType::Rigid);
|
EAttachmentType InAttachmentType = EAttachmentType::Rigid,
|
||||||
|
const FString& SocketName = "");
|
||||||
|
|
||||||
/// @copydoc FActorDispatcher::DestroyActor(AActor*)
|
/// @copydoc FActorDispatcher::DestroyActor(AActor*)
|
||||||
UFUNCTION(BlueprintCallable)
|
UFUNCTION(BlueprintCallable)
|
||||||
|
|
|
@ -9,6 +9,11 @@
|
||||||
#include "Carla/Server/CarlaServerResponse.h"
|
#include "Carla/Server/CarlaServerResponse.h"
|
||||||
#include "Carla/Traffic/TrafficLightGroup.h"
|
#include "Carla/Traffic/TrafficLightGroup.h"
|
||||||
#include "EngineUtils.h"
|
#include "EngineUtils.h"
|
||||||
|
#include "Components/SkeletalMeshComponent.h"
|
||||||
|
#include "Components/SkinnedMeshComponent.h"
|
||||||
|
#include "Components/SceneComponent.h"
|
||||||
|
#include "Engine/SkeletalMesh.h"
|
||||||
|
#include "Engine/SkeletalMeshSocket.h"
|
||||||
|
|
||||||
#include "Carla/OpenDrive/OpenDrive.h"
|
#include "Carla/OpenDrive/OpenDrive.h"
|
||||||
#include "Carla/Util/DebugShapeDrawer.h"
|
#include "Carla/Util/DebugShapeDrawer.h"
|
||||||
|
@ -706,7 +711,8 @@ void FCarlaServer::FPimpl::BindActions()
|
||||||
cr::ActorDescription Description,
|
cr::ActorDescription Description,
|
||||||
const cr::Transform &Transform,
|
const cr::Transform &Transform,
|
||||||
cr::ActorId ParentId,
|
cr::ActorId ParentId,
|
||||||
cr::AttachmentType InAttachmentType) -> R<cr::Actor>
|
cr::AttachmentType InAttachmentType,
|
||||||
|
const std::string& socket_name) -> R<cr::Actor>
|
||||||
{
|
{
|
||||||
REQUIRE_CARLA_EPISODE();
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
|
||||||
|
@ -760,7 +766,8 @@ void FCarlaServer::FPimpl::BindActions()
|
||||||
Episode->AttachActors(
|
Episode->AttachActors(
|
||||||
CarlaActor->GetActor(),
|
CarlaActor->GetActor(),
|
||||||
ParentCarlaActor->GetActor(),
|
ParentCarlaActor->GetActor(),
|
||||||
static_cast<EAttachmentType>(InAttachmentType));
|
static_cast<EAttachmentType>(InAttachmentType),
|
||||||
|
FString(socket_name.c_str()));
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -1274,6 +1281,305 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_
|
||||||
return R<void>::Success();
|
return R<void>::Success();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_component_world_transform) << [this](
|
||||||
|
cr::ActorId ActorId,
|
||||||
|
const std::string componentName) -> R<cr::Transform>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_world_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<UActorComponent*> Components;
|
||||||
|
CarlaActor->GetActor()->GetComponents(Components);
|
||||||
|
|
||||||
|
USceneComponent* Component = nullptr;
|
||||||
|
for(auto Cmp : Components)
|
||||||
|
{
|
||||||
|
if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
|
||||||
|
{
|
||||||
|
if(SCMP->GetName() == componentName.c_str())
|
||||||
|
{
|
||||||
|
Component = SCMP;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(!Component)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_world_transform",
|
||||||
|
ECarlaServerResponse::ComponentNotFound,
|
||||||
|
" Component Name: " + FString(componentName.c_str()));
|
||||||
|
}
|
||||||
|
|
||||||
|
FTransform ComponentWorldTransform = Component->GetComponentTransform();
|
||||||
|
return cr::Transform(ComponentWorldTransform);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_component_relative_transform) << [this](
|
||||||
|
cr::ActorId ActorId,
|
||||||
|
const std::string componentName) -> R<cr::Transform>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_relative_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<UActorComponent*> Components;
|
||||||
|
CarlaActor->GetActor()->GetComponents(Components);
|
||||||
|
|
||||||
|
USceneComponent* Component = nullptr;
|
||||||
|
for(auto Cmp : Components)
|
||||||
|
{
|
||||||
|
if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
|
||||||
|
{
|
||||||
|
if(SCMP->GetName() == componentName.c_str())
|
||||||
|
{
|
||||||
|
Component = SCMP;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(!Component)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_world_transform",
|
||||||
|
ECarlaServerResponse::ComponentNotFound,
|
||||||
|
" Component Name: " + FString(componentName.c_str()));
|
||||||
|
}
|
||||||
|
|
||||||
|
FTransform ComponentRelativeTransform = Component->GetRelativeTransform();
|
||||||
|
return cr::Transform(ComponentRelativeTransform);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_bone_world_transforms) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_bone_world_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<FTransform> BoneWorldTransforms;
|
||||||
|
TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
|
||||||
|
CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
|
||||||
|
if(!SkinnedMeshComponents[0])
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_bone_relative_transforms",
|
||||||
|
ECarlaServerResponse::ComponentNotFound,
|
||||||
|
" Component Name: SkinnedMeshComponent ");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
|
||||||
|
{
|
||||||
|
const int32 NumBones = SkinnedMeshComponent->GetNumBones();
|
||||||
|
for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
|
||||||
|
{
|
||||||
|
FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform();
|
||||||
|
FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform);
|
||||||
|
BoneWorldTransforms.Add(BoneTransform);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return MakeVectorFromTArray<cr::Transform>(BoneWorldTransforms);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_bone_relative_transforms) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_bone_relative_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<FTransform> BoneRelativeTransforms;
|
||||||
|
TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
|
||||||
|
CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
|
||||||
|
if(!SkinnedMeshComponents[0])
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_bone_relative_transforms",
|
||||||
|
ECarlaServerResponse::ComponentNotFound,
|
||||||
|
" Component Name: SkinnedMeshComponent ");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
|
||||||
|
{
|
||||||
|
const int32 NumBones = SkinnedMeshComponent->GetNumBones();
|
||||||
|
for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
|
||||||
|
{
|
||||||
|
FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity);
|
||||||
|
BoneRelativeTransforms.Add(BoneTransform);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return MakeVectorFromTArray<cr::Transform>(BoneRelativeTransforms);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_component_names) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<std::string>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_names",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<UActorComponent*> Components;
|
||||||
|
CarlaActor->GetActor()->GetComponents(Components);
|
||||||
|
std::vector<std::string> ComponentNames;
|
||||||
|
for(auto Cmp : Components)
|
||||||
|
{
|
||||||
|
FString ComponentName = Cmp->GetName();
|
||||||
|
ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName));
|
||||||
|
}
|
||||||
|
return ComponentNames;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_bone_names) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<std::string>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_relative_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->GetActor()->FindComponentByClass<USkinnedMeshComponent>();
|
||||||
|
if(!SkinnedMeshComponent)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_bone_relative_transforms",
|
||||||
|
ECarlaServerResponse::ComponentNotFound,
|
||||||
|
" Component Name: SkinnedMeshComponent ");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<FName> BoneNames;
|
||||||
|
SkinnedMeshComponent->GetBoneNames(BoneNames);
|
||||||
|
TArray<std::string> StringBoneNames;
|
||||||
|
for (const FName& Name : BoneNames)
|
||||||
|
{
|
||||||
|
FString FBoneName = Name.ToString();
|
||||||
|
std::string StringBoneName = TCHAR_TO_UTF8(*FBoneName);
|
||||||
|
StringBoneNames.Add(StringBoneName);
|
||||||
|
}
|
||||||
|
return MakeVectorFromTArray<std::string>(StringBoneNames);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_socket_world_transforms) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_relative_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<FTransform> SocketWorldTransforms;
|
||||||
|
TArray<UActorComponent*> Components;
|
||||||
|
CarlaActor->GetActor()->GetComponents(Components);
|
||||||
|
for(UActorComponent* ActorComponent : Components)
|
||||||
|
{
|
||||||
|
if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
|
||||||
|
{
|
||||||
|
const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
|
||||||
|
for (const FName& SocketName : SocketNames)
|
||||||
|
{
|
||||||
|
FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName);
|
||||||
|
SocketWorldTransforms.Add(SocketTransform);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return MakeVectorFromTArray<cr::Transform>(SocketWorldTransforms);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
BIND_SYNC(get_actor_socket_relative_transforms) << [this](
|
||||||
|
cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
|
||||||
|
{
|
||||||
|
REQUIRE_CARLA_EPISODE();
|
||||||
|
FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
|
||||||
|
if (!CarlaActor)
|
||||||
|
{
|
||||||
|
return RespondError(
|
||||||
|
"get_actor_component_relative_transform",
|
||||||
|
ECarlaServerResponse::ActorNotFound,
|
||||||
|
" Actor Id: " + FString::FromInt(ActorId));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
TArray<FTransform> SocketRelativeTransforms;
|
||||||
|
TArray<UActorComponent*> Components;
|
||||||
|
CarlaActor->GetActor()->GetComponents(Components);
|
||||||
|
for(UActorComponent* ActorComponent : Components)
|
||||||
|
{
|
||||||
|
if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
|
||||||
|
{
|
||||||
|
const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
|
||||||
|
for (const FName& SocketName : SocketNames)
|
||||||
|
{
|
||||||
|
FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor);
|
||||||
|
SocketRelativeTransforms.Add(SocketTransform);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return MakeVectorFromTArray<cr::Transform>(SocketRelativeTransforms);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
BIND_SYNC(get_physics_control) << [this](
|
BIND_SYNC(get_physics_control) << [this](
|
||||||
cr::ActorId ActorId) -> R<cr::VehiclePhysicsControl>
|
cr::ActorId ActorId) -> R<cr::VehiclePhysicsControl>
|
||||||
{
|
{
|
||||||
|
@ -2457,7 +2763,8 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_
|
||||||
c.description,
|
c.description,
|
||||||
c.transform,
|
c.transform,
|
||||||
*c.parent,
|
*c.parent,
|
||||||
cr::AttachmentType::Rigid) :
|
cr::AttachmentType::Rigid,
|
||||||
|
c.socket_name) :
|
||||||
spawn_actor(c.description, c.transform);
|
spawn_actor(c.description, c.transform);
|
||||||
if (!result.HasError())
|
if (!result.HasError())
|
||||||
{
|
{
|
||||||
|
|
|
@ -14,6 +14,8 @@ FString CarlaGetStringError(ECarlaServerResponse Response)
|
||||||
return "Sucess";
|
return "Sucess";
|
||||||
case ECarlaServerResponse::ActorNotFound:
|
case ECarlaServerResponse::ActorNotFound:
|
||||||
return "Actor could not be found in the registry";
|
return "Actor could not be found in the registry";
|
||||||
|
case ECarlaServerResponse::ComponentNotFound:
|
||||||
|
return "Component could not be found in this actor";
|
||||||
case ECarlaServerResponse::ActorTypeMismatch:
|
case ECarlaServerResponse::ActorTypeMismatch:
|
||||||
return "Actor does not match the expected type";
|
return "Actor does not match the expected type";
|
||||||
case ECarlaServerResponse::MissingActor:
|
case ECarlaServerResponse::MissingActor:
|
||||||
|
|
|
@ -10,6 +10,7 @@ enum class ECarlaServerResponse
|
||||||
{
|
{
|
||||||
Success,
|
Success,
|
||||||
ActorNotFound,
|
ActorNotFound,
|
||||||
|
ComponentNotFound,
|
||||||
ActorTypeMismatch,
|
ActorTypeMismatch,
|
||||||
FunctionNotSupported,
|
FunctionNotSupported,
|
||||||
NullActor,
|
NullActor,
|
||||||
|
|
|
@ -96,7 +96,8 @@ static void UActorAttacher_AttachActorsWithSpringArmGhost(
|
||||||
void UActorAttacher::AttachActors(
|
void UActorAttacher::AttachActors(
|
||||||
AActor *Child,
|
AActor *Child,
|
||||||
AActor *Parent,
|
AActor *Parent,
|
||||||
const EAttachmentType AttachmentType)
|
const EAttachmentType AttachmentType,
|
||||||
|
const FString& SocketName)
|
||||||
{
|
{
|
||||||
check(Child != nullptr);
|
check(Child != nullptr);
|
||||||
check(Parent != nullptr);
|
check(Parent != nullptr);
|
||||||
|
@ -104,7 +105,7 @@ void UActorAttacher::AttachActors(
|
||||||
switch (AttachmentType)
|
switch (AttachmentType)
|
||||||
{
|
{
|
||||||
case EAttachmentType::Rigid:
|
case EAttachmentType::Rigid:
|
||||||
Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform);
|
Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform, FName(*SocketName));
|
||||||
break;
|
break;
|
||||||
case EAttachmentType::SpringArm:
|
case EAttachmentType::SpringArm:
|
||||||
UActorAttacher_AttachActorsWithSpringArm(Child, Parent);
|
UActorAttacher_AttachActorsWithSpringArm(Child, Parent);
|
||||||
|
|
|
@ -42,5 +42,5 @@ class CARLA_API UActorAttacher : public UBlueprintFunctionLibrary
|
||||||
public:
|
public:
|
||||||
|
|
||||||
UFUNCTION(BlueprintCallable, Category="CARLA|Actor Attacher")
|
UFUNCTION(BlueprintCallable, Category="CARLA|Actor Attacher")
|
||||||
static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType);
|
static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType, const FString& SocketName = "");
|
||||||
};
|
};
|
||||||
|
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -154,6 +154,8 @@ void UOpenDriveToMap::CreateMap()
|
||||||
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Map Name Is Empty") );
|
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Map Name Is Empty") );
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if( !Url.IsEmpty() ) {
|
||||||
if ( !IsValid(FileDownloader) )
|
if ( !IsValid(FileDownloader) )
|
||||||
{
|
{
|
||||||
FileDownloader = NewObject<UCustomFileDownloader>();
|
FileDownloader = NewObject<UCustomFileDownloader>();
|
||||||
|
@ -165,6 +167,20 @@ void UOpenDriveToMap::CreateMap()
|
||||||
FileDownloader->DownloadDelegate.BindUObject( this, &UOpenDriveToMap::ConvertOSMInOpenDrive );
|
FileDownloader->DownloadDelegate.BindUObject( this, &UOpenDriveToMap::ConvertOSMInOpenDrive );
|
||||||
FileDownloader->StartDownload();
|
FileDownloader->StartDownload();
|
||||||
}
|
}
|
||||||
|
else if(LocalFilePath.EndsWith(".xodr"))
|
||||||
|
{
|
||||||
|
ImportXODR();
|
||||||
|
}
|
||||||
|
else if(LocalFilePath.EndsWith(".osm"))
|
||||||
|
{
|
||||||
|
ImportOSM();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("URL and Local FilePath are Empty. URL: %s Local FilePath: %s"), *Url, *LocalFilePath );
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
void UOpenDriveToMap::CreateTerrain( const int MeshGridSize, const float MeshGridSectionSize)
|
void UOpenDriveToMap::CreateTerrain( const int MeshGridSize, const float MeshGridSectionSize)
|
||||||
{
|
{
|
||||||
|
@ -490,7 +506,7 @@ void UOpenDriveToMap::GenerateAll(const boost::optional<carla::road::Map>& Param
|
||||||
{
|
{
|
||||||
GenerateRoadMesh(ParamCarlaMap, MinLocation, MaxLocation);
|
GenerateRoadMesh(ParamCarlaMap, MinLocation, MaxLocation);
|
||||||
GenerateLaneMarks(ParamCarlaMap, MinLocation, MaxLocation);
|
GenerateLaneMarks(ParamCarlaMap, MinLocation, MaxLocation);
|
||||||
//GenerateSpawnPoints(ParamCarlaMap);
|
GenerateSpawnPoints(ParamCarlaMap, MinLocation, MaxLocation);
|
||||||
CreateTerrain(12800, 256);
|
CreateTerrain(12800, 256);
|
||||||
GenerateTreePositions(ParamCarlaMap, MinLocation, MaxLocation);
|
GenerateTreePositions(ParamCarlaMap, MinLocation, MaxLocation);
|
||||||
GenerationFinished(MinLocation, MaxLocation);
|
GenerationFinished(MinLocation, MaxLocation);
|
||||||
|
@ -714,12 +730,16 @@ void UOpenDriveToMap::GenerateSpawnPoints( const boost::optional<carla::road::Ma
|
||||||
for (const auto &Wp : Waypoints)
|
for (const auto &Wp : Waypoints)
|
||||||
{
|
{
|
||||||
const FTransform Trans = ParamCarlaMap->ComputeTransform(Wp);
|
const FTransform Trans = ParamCarlaMap->ComputeTransform(Wp);
|
||||||
|
if( Trans.GetLocation().X >= MinLocation.X && Trans.GetLocation().Y >= MinLocation.Y &&
|
||||||
|
Trans.GetLocation().X <= MaxLocation.X && Trans.GetLocation().Y <= MaxLocation.Y)
|
||||||
|
{
|
||||||
AVehicleSpawnPoint *Spawner = UEditorLevelLibrary::GetEditorWorld()->SpawnActor<AVehicleSpawnPoint>();
|
AVehicleSpawnPoint *Spawner = UEditorLevelLibrary::GetEditorWorld()->SpawnActor<AVehicleSpawnPoint>();
|
||||||
Spawner->SetActorRotation(Trans.GetRotation());
|
Spawner->SetActorRotation(Trans.GetRotation());
|
||||||
Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight));
|
Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight));
|
||||||
ActorsToMove.Add(Spawner);
|
ActorsToMove.Add(Spawner);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void UOpenDriveToMap::GenerateTreePositions( const boost::optional<carla::road::Map>& ParamCarlaMap, FVector MinLocation, FVector MaxLocation )
|
void UOpenDriveToMap::GenerateTreePositions( const boost::optional<carla::road::Map>& ParamCarlaMap, FVector MinLocation, FVector MaxLocation )
|
||||||
{
|
{
|
||||||
|
@ -878,6 +898,41 @@ bool UOpenDriveToMap::IsInRoad(
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void UOpenDriveToMap::ImportXODR(){
|
||||||
|
IPlatformFile& FileManager = FPlatformFileManager::Get().GetPlatformFile();
|
||||||
|
FString MyFileDestination = FPaths::ProjectContentDir() + "CustomMaps/" + MapName + "/OpenDrive/" + MapName + ".xodr";
|
||||||
|
|
||||||
|
if(FileManager.CopyFile( *MyFileDestination, *LocalFilePath,
|
||||||
|
EPlatformFileRead::None,
|
||||||
|
EPlatformFileWrite::None))
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaToolsMapGenerator, Verbose, TEXT("FilePaths: File Copied!"));
|
||||||
|
FilePath = MyFileDestination;
|
||||||
|
LoadMap();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("FilePaths local xodr file not copied: File not Copied!"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void UOpenDriveToMap::ImportOSM(){
|
||||||
|
IPlatformFile& FileManager = FPlatformFileManager::Get().GetPlatformFile();
|
||||||
|
FString MyFileDestination = FPaths::ProjectContentDir() + "CustomMaps/" + MapName + "/OpenDrive/" + MapName + ".osm";
|
||||||
|
|
||||||
|
if(FileManager.CopyFile( *MyFileDestination, *LocalFilePath,
|
||||||
|
EPlatformFileRead::None,
|
||||||
|
EPlatformFileWrite::None))
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaToolsMapGenerator, Verbose, TEXT("FilePaths: File Copied!"));
|
||||||
|
ConvertOSMInOpenDrive();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("FilePaths local osm file not copied: File not Copied!"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void UOpenDriveToMap::MoveActorsToSubLevels(TArray<AActor*> ActorsToMove)
|
void UOpenDriveToMap::MoveActorsToSubLevels(TArray<AActor*> ActorsToMove)
|
||||||
{
|
{
|
||||||
AActor* QueryActor = UGameplayStatics::GetActorOfClass(
|
AActor* QueryActor = UGameplayStatics::GetActorOfClass(
|
||||||
|
|
|
@ -91,6 +91,9 @@ public:
|
||||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||||
FString Url;
|
FString Url;
|
||||||
|
|
||||||
|
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||||
|
FString LocalFilePath;
|
||||||
|
|
||||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Settings")
|
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Settings")
|
||||||
FVector2D OriginGeoCoordinates;
|
FVector2D OriginGeoCoordinates;
|
||||||
|
|
||||||
|
@ -213,6 +216,9 @@ private:
|
||||||
|
|
||||||
void InitTextureData();
|
void InitTextureData();
|
||||||
|
|
||||||
|
void ImportXODR();
|
||||||
|
void ImportOSM();
|
||||||
|
|
||||||
UPROPERTY()
|
UPROPERTY()
|
||||||
UCustomFileDownloader* FileDownloader;
|
UCustomFileDownloader* FileDownloader;
|
||||||
UPROPERTY()
|
UPROPERTY()
|
||||||
|
|
|
@ -155,10 +155,10 @@ if exist %OMNIVERSE_PLUGIN_FOLDER% (
|
||||||
)
|
)
|
||||||
|
|
||||||
if %USE_CARSIM% == true (
|
if %USE_CARSIM% == true (
|
||||||
py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e
|
python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e
|
||||||
set CARSIM_STATE="CarSim ON"
|
set CARSIM_STATE="CarSim ON"
|
||||||
) else (
|
) else (
|
||||||
py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject"
|
python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject"
|
||||||
set CARSIM_STATE="CarSim OFF"
|
set CARSIM_STATE="CarSim OFF"
|
||||||
)
|
)
|
||||||
if %USE_CHRONO% == true (
|
if %USE_CHRONO% == true (
|
||||||
|
|
|
@ -109,7 +109,7 @@ rem Build for Python 3
|
||||||
rem
|
rem
|
||||||
if %BUILD_FOR_PYTHON3%==true (
|
if %BUILD_FOR_PYTHON3%==true (
|
||||||
echo Building Python API for Python 3.
|
echo Building Python API for Python 3.
|
||||||
py -3 setup.py bdist_egg bdist_wheel
|
python setup.py bdist_egg bdist_wheel
|
||||||
if %errorlevel% neq 0 goto error_build_wheel
|
if %errorlevel% neq 0 goto error_build_wheel
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
|
@ -119,10 +119,10 @@ rem ============================================================================
|
||||||
if %DO_PACKAGE%==true (
|
if %DO_PACKAGE%==true (
|
||||||
|
|
||||||
if %USE_CARSIM% == true (
|
if %USE_CARSIM% == true (
|
||||||
py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e
|
python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject" -e
|
||||||
echo CarSim ON > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini"
|
echo CarSim ON > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini"
|
||||||
) else (
|
) else (
|
||||||
py -3 %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject"
|
python %ROOT_PATH%Util/BuildTools/enable_carsim_to_uproject.py -f="%ROOT_PATH%Unreal/CarlaUE4/CarlaUE4.uproject"
|
||||||
echo CarSim OFF > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini"
|
echo CarSim OFF > "%ROOT_PATH%Unreal/CarlaUE4/Config/CarSimConfig.ini"
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
|
@ -92,15 +92,30 @@ for PY_VERSION in ${PY_VERSION_LIST[@]} ; do
|
||||||
BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_}
|
BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_}
|
||||||
|
|
||||||
log "Retrieving boost."
|
log "Retrieving boost."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true
|
wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" || true
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading from boost webpage: $(($end-$start)) seconds"
|
||||||
|
|
||||||
# try to use the backup boost we have in Jenkins
|
# try to use the backup boost we have in Jenkins
|
||||||
if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz") != "${BOOST_SHA256SUM}" ]] ; then
|
if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz") != "${BOOST_SHA256SUM}" ]] ; then
|
||||||
log "Using boost backup"
|
log "Using boost backup"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true
|
wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" || true
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading from boost carla backup in backblaze: $(($end-$start)) seconds"
|
||||||
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
log "Extracting boost for Python ${PY_VERSION}."
|
log "Extracting boost for Python ${PY_VERSION}."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz
|
tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting boost for Python: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mkdir -p ${BOOST_BASENAME}-install/include
|
mkdir -p ${BOOST_BASENAME}-install/include
|
||||||
mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source
|
mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source
|
||||||
|
|
||||||
|
@ -166,8 +181,13 @@ else
|
||||||
|
|
||||||
log "Retrieving rpclib."
|
log "Retrieving rpclib."
|
||||||
|
|
||||||
|
start_download_time=$(date +%s)
|
||||||
|
|
||||||
git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source
|
git clone -b ${RPCLIB_PATCH} https://github.com/carla-simulator/rpclib.git ${RPCLIB_BASENAME}-source
|
||||||
|
|
||||||
|
end_download_time=$(date +%s)
|
||||||
|
|
||||||
|
echo "Elapsed Time downloading rpclib: $(($end_download_time-$start_download_time)) seconds"
|
||||||
log "Building rpclib with libc++."
|
log "Building rpclib with libc++."
|
||||||
|
|
||||||
# rpclib does not use any cmake 3.9 feature.
|
# rpclib does not use any cmake 3.9 feature.
|
||||||
|
@ -234,8 +254,13 @@ else
|
||||||
|
|
||||||
log "Retrieving Google Test."
|
log "Retrieving Google Test."
|
||||||
|
|
||||||
|
start_download_time=$(date +%s)
|
||||||
|
|
||||||
git clone --depth=1 -b release-${GTEST_VERSION} https://github.com/google/googletest.git ${GTEST_BASENAME}-source
|
git clone --depth=1 -b release-${GTEST_VERSION} https://github.com/google/googletest.git ${GTEST_BASENAME}-source
|
||||||
|
|
||||||
|
end_download_time=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading rpclib: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Building Google Test with libc++."
|
log "Building Google Test with libc++."
|
||||||
|
|
||||||
mkdir -p ${GTEST_BASENAME}-libcxx-build
|
mkdir -p ${GTEST_BASENAME}-libcxx-build
|
||||||
|
@ -296,12 +321,15 @@ else
|
||||||
|
|
||||||
log "Retrieving Recast & Detour"
|
log "Retrieving Recast & Detour"
|
||||||
|
|
||||||
git clone https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source
|
start=$(date +%s)
|
||||||
|
|
||||||
|
git clone --depth 1 -b carla https://github.com/carla-simulator/recastnavigation.git ${RECAST_BASENAME}-source
|
||||||
|
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading: $(($end-$start)) seconds"
|
||||||
|
|
||||||
pushd ${RECAST_BASENAME}-source >/dev/null
|
pushd ${RECAST_BASENAME}-source >/dev/null
|
||||||
|
|
||||||
git checkout carla
|
|
||||||
|
|
||||||
popd >/dev/null
|
popd >/dev/null
|
||||||
|
|
||||||
log "Building Recast & Detour with libc++."
|
log "Building Recast & Detour with libc++."
|
||||||
|
@ -351,10 +379,18 @@ if [[ -d ${LIBPNG_INSTALL} ]] ; then
|
||||||
log "Libpng already installed."
|
log "Libpng already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving libpng."
|
log "Retrieving libpng."
|
||||||
wget ${LIBPNG_REPO}
|
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
|
wget ${LIBPNG_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading libpng: $(($end-$start)) seconds"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
log "Extracting libpng."
|
log "Extracting libpng."
|
||||||
tar -xf libpng-${LIBPNG_VERSION}.tar.xz
|
tar -xf libpng-${LIBPNG_VERSION}.tar.xz
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting libpng: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${LIBPNG_BASENAME} ${LIBPNG_BASENAME}-source
|
mv ${LIBPNG_BASENAME} ${LIBPNG_BASENAME}-source
|
||||||
|
|
||||||
pushd ${LIBPNG_BASENAME}-source >/dev/null
|
pushd ${LIBPNG_BASENAME}-source >/dev/null
|
||||||
|
@ -388,16 +424,26 @@ if [[ -d ${XERCESC_INSTALL_DIR} && -d ${XERCESC_INSTALL_SERVER_DIR} ]] ; then
|
||||||
log "Xerces-c already installed."
|
log "Xerces-c already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving xerces-c."
|
log "Retrieving xerces-c."
|
||||||
|
start=$(date +%s)
|
||||||
wget ${XERCESC_REPO}
|
wget ${XERCESC_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading from xerces repo: $(($end-$start)) seconds"
|
||||||
# try to use the backup boost we have in Jenkins
|
# try to use the backup boost we have in Jenkins
|
||||||
if [[ ! -f "${XERCESC_BASENAME}.tar.gz" ]] ; then
|
if [[ ! -f "${XERCESC_BASENAME}.tar.gz" ]] ; then
|
||||||
log "Using xerces backup"
|
log "Using xerces backup"
|
||||||
|
start=$(date +%s)
|
||||||
wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${XERCESC_BASENAME}.tar.gz" || true
|
wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${XERCESC_BASENAME}.tar.gz" || true
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading from xerces backup: $(($end-$start)) seconds"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
log "Extracting xerces-c."
|
log "Extracting xerces-c."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${XERCESC_BASENAME}.tar.gz
|
tar -xzf ${XERCESC_BASENAME}.tar.gz
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting xerces-c: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR}
|
mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR}
|
||||||
mkdir -p ${XERCESC_INSTALL_DIR}
|
mkdir -p ${XERCESC_INSTALL_DIR}
|
||||||
mkdir -p ${XERCESC_SRC_DIR}/build
|
mkdir -p ${XERCESC_SRC_DIR}/build
|
||||||
|
@ -461,10 +507,18 @@ if [[ -d ${EIGEN_INSTALL_DIR} ]] ; then
|
||||||
log "Eigen already installed."
|
log "Eigen already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving Eigen."
|
log "Retrieving Eigen."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${EIGEN_REPO}
|
wget ${EIGEN_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading from eigen repo: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Extracting Eigen."
|
log "Extracting Eigen."
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${EIGEN_BASENAME}.tar.gz
|
tar -xzf ${EIGEN_BASENAME}.tar.gz
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting EIGEN: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR}
|
mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR}
|
||||||
mkdir -p ${EIGEN_INCLUDE}/unsupported
|
mkdir -p ${EIGEN_INCLUDE}/unsupported
|
||||||
mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE}
|
mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE}
|
||||||
|
@ -496,10 +550,19 @@ if ${USE_CHRONO} ; then
|
||||||
log "Eigen already installed."
|
log "Eigen already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving Eigen."
|
log "Retrieving Eigen."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${EIGEN_REPO}
|
wget ${EIGEN_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Extracting Eigen."
|
log "Extracting Eigen."
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${EIGEN_BASENAME}.tar.gz
|
tar -xzf ${EIGEN_BASENAME}.tar.gz
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting for Eigen: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR}
|
mv ${EIGEN_BASENAME} ${EIGEN_SRC_DIR}
|
||||||
mkdir -p ${EIGEN_INCLUDE}/unsupported
|
mkdir -p ${EIGEN_INCLUDE}/unsupported
|
||||||
mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE}
|
mv ${EIGEN_SRC_DIR}/Eigen ${EIGEN_INCLUDE}
|
||||||
|
@ -527,7 +590,10 @@ if ${USE_CHRONO} ; then
|
||||||
log "chrono library already installed."
|
log "chrono library already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving chrono library."
|
log "Retrieving chrono library."
|
||||||
|
start=$(date +%s)
|
||||||
git clone --depth 1 --branch ${CHRONO_TAG} ${CHRONO_REPO} ${CHRONO_SRC_DIR}
|
git clone --depth 1 --branch ${CHRONO_TAG} ${CHRONO_REPO} ${CHRONO_SRC_DIR}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time dowloading chrono: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mkdir -p ${CHRONO_SRC_DIR}/build
|
mkdir -p ${CHRONO_SRC_DIR}/build
|
||||||
|
|
||||||
|
@ -574,10 +640,19 @@ if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then
|
||||||
log "Sqlite already installed."
|
log "Sqlite already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving Sqlite3"
|
log "Retrieving Sqlite3"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${SQLITE_REPO}
|
wget ${SQLITE_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Extracting Sqlite3"
|
log "Extracting Sqlite3"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${SQLITE_TAR}
|
tar -xzf ${SQLITE_TAR}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting for SQlite: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR}
|
mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR}
|
||||||
|
|
||||||
mkdir ${SQLITE_INSTALL_DIR}
|
mkdir ${SQLITE_INSTALL_DIR}
|
||||||
|
@ -621,10 +696,18 @@ if [[ -d ${PROJ_INSTALL_DIR} && -d ${PROJ_INSTALL_SERVER_DIR_FULL} ]] ; then
|
||||||
log "PROJ already installed."
|
log "PROJ already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving PROJ"
|
log "Retrieving PROJ"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${PROJ_REPO}
|
wget ${PROJ_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Extracting PROJ"
|
log "Extracting PROJ"
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${PROJ_TAR}
|
tar -xzf ${PROJ_TAR}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting for PROJ: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv ${PROJ_VERSION} ${PROJ_SRC_DIR}
|
mv ${PROJ_VERSION} ${PROJ_SRC_DIR}
|
||||||
|
|
||||||
mkdir -p ${PROJ_SRC_DIR}/build
|
mkdir -p ${PROJ_SRC_DIR}/build
|
||||||
|
@ -692,10 +775,18 @@ if [[ -d ${PATCHELF_INSTALL_DIR} ]] ; then
|
||||||
log "Patchelf already installed."
|
log "Patchelf already installed."
|
||||||
else
|
else
|
||||||
log "Retrieving patchelf"
|
log "Retrieving patchelf"
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${PATCHELF_REPO}
|
wget ${PATCHELF_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time: $(($end-$start)) seconds"
|
||||||
|
|
||||||
log "Extracting patchelf"
|
log "Extracting patchelf"
|
||||||
|
start=$(date +%s)
|
||||||
tar -xzf ${PATCHELF_TAR}
|
tar -xzf ${PATCHELF_TAR}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time Extracting patchelf: $(($end-$start)) seconds"
|
||||||
|
|
||||||
mv patchelf-${PATCHELF_VERSION} ${PATCHELF_SOURCE_DIR}
|
mv patchelf-${PATCHELF_VERSION} ${PATCHELF_SOURCE_DIR}
|
||||||
|
|
||||||
mkdir ${PATCHELF_INSTALL_DIR}
|
mkdir ${PATCHELF_INSTALL_DIR}
|
||||||
|
@ -730,7 +821,12 @@ if ${USE_PYTORCH} ; then
|
||||||
LIBTORCH_ZIPFILE=libtorch-shared-with-deps-1.11.0+cu113.zip
|
LIBTORCH_ZIPFILE=libtorch-shared-with-deps-1.11.0+cu113.zip
|
||||||
LIBTORCH_REPO=https://download.pytorch.org/libtorch/cu113/libtorch-shared-with-deps-1.11.0%2Bcu113.zip
|
LIBTORCH_REPO=https://download.pytorch.org/libtorch/cu113/libtorch-shared-with-deps-1.11.0%2Bcu113.zip
|
||||||
if [[ ! -d ${LIBTORCH_PATH} ]] ; then
|
if [[ ! -d ${LIBTORCH_PATH} ]] ; then
|
||||||
|
|
||||||
|
start=$(date +%s)
|
||||||
wget ${LIBTORCH_REPO}
|
wget ${LIBTORCH_REPO}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time downloading LIBTORCH_REPO: $(($end-$start)) seconds"
|
||||||
|
|
||||||
unzip ${LIBTORCH_ZIPFILE}
|
unzip ${LIBTORCH_ZIPFILE}
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
@ -810,7 +906,10 @@ if ${USE_ROS2} ; then
|
||||||
if [[ ! -d ${LIB_SOURCE} ]] ; then
|
if [[ ! -d ${LIB_SOURCE} ]] ; then
|
||||||
mkdir -p ${LIB_SOURCE}
|
mkdir -p ${LIB_SOURCE}
|
||||||
log "${LIB_REPO}"
|
log "${LIB_REPO}"
|
||||||
|
start=$(date +%s)
|
||||||
git clone --depth 1 --branch ${LIB_BRANCH} ${LIB_REPO} ${LIB_SOURCE}
|
git clone --depth 1 --branch ${LIB_BRANCH} ${LIB_REPO} ${LIB_SOURCE}
|
||||||
|
end=$(date +%s)
|
||||||
|
echo "Elapsed Time dowloading fastdds extension: $(($end-$start)) seconds"
|
||||||
mkdir -p ${LIB_SOURCE}/build
|
mkdir -p ${LIB_SOURCE}/build
|
||||||
fi
|
fi
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue