New sensor: Inertial measurement unit (IMU) (#2220)
* Added IMU sensor to the client-server pipeline * Fixed lane_explorer.py with the new debug API * Changed compass output to standard compass degrees * - Added accelerometer calculation to IMU. * Added angular velocity to the IMU * Changed IMU acceleration from world to local * Updated changelog * Updated accelerometer. Now uses vehicle movement component information instead of pawn information. * Added docs regardings new sensors * Fixed SI units in Lidar * Fixed core dumped when using other python modules * Explicitly deleted Vec3D from FVec constructors * Removed redundant DeltaTime calculation
This commit is contained in:
parent
714f8c4cbf
commit
6187bf4916
|
@ -1,5 +1,11 @@
|
|||
## Latest
|
||||
* Added new sensor: Inertial measurement unit (IMU)
|
||||
* Now all the camera-based sensors are provided with an additional parametrized lens distortion shader
|
||||
* API changes:
|
||||
- Lidar: `range` is now set in meters, not in centimeters
|
||||
- Lidar: `horizontal_angle` is now received in radians, not in degrees
|
||||
* API extensions:
|
||||
- Added `carla.IMUMeasurement`
|
||||
* Updated manual_control.py with a lens disortion effect example
|
||||
* Exposed rgb camera attributes: exposure, depth of field, tonemapper, color correction, and chromatic aberration
|
||||
* Fixed pylint for python3 in travis
|
||||
|
|
|
@ -26,14 +26,15 @@ And for the **props** folder, we will need the following files:
|
|||
|
||||
Additionally, we have to create a **JSON file inside the package** that will contain information
|
||||
about its assets. The file extension must be `.json`. We recommend the JSON file to have the same
|
||||
name as the package name in order to keep it organized.
|
||||
name as the package name in order to keep it organized.
|
||||
**Please, keep in mind that the name of this file will used as the name of the distribution package**.
|
||||
|
||||
The content of this JSON file should be similar to the following:
|
||||
|
||||
```json
|
||||
{
|
||||
"maps": [{
|
||||
"maps": [
|
||||
{
|
||||
"name": "MyTown01",
|
||||
"source": "./MapToImport01/MapToImport01.fbx",
|
||||
"use_carla_materials": true,
|
||||
|
@ -46,7 +47,8 @@ The content of this JSON file should be similar to the following:
|
|||
"xodr": "./MapToImport02/MapToImport02.xodr"
|
||||
}
|
||||
],
|
||||
"props": [{
|
||||
"props": [
|
||||
{
|
||||
"name": "MyProp01",
|
||||
"size": "medium",
|
||||
"source": "./AssetsToImport/PropToImport01/PropToImport01.fbx",
|
||||
|
@ -100,7 +102,7 @@ name and, if so, it will create separate mesh files inside Unreal for each diffe
|
|||
- `Vegetation`
|
||||
- `Vehicles`
|
||||
- `Walls`
|
||||
|
||||
|
||||
Note that if the tag is not spelled correctly, it will interpret it as `None` value by default.
|
||||
|
||||
To sum up, the `Import` folder should have this similar structure:
|
||||
|
|
|
@ -304,7 +304,7 @@ supposed to generate this frame; `points_per_second / (FPS * channels)`.
|
|||
| Blueprint attribute | Type | Default | Description |
|
||||
| -------------------- | ---- | ------- | ----------- |
|
||||
| `channels` | int | 32 | Number of lasers |
|
||||
| `range` | float | 1000 | Maximum measurement distance in centimeters |
|
||||
| `range` | float | 10.0 | Maximum measurement distance in meters _(<=0.9.6: is in centimeters)_ |
|
||||
| `points_per_second` | int | 56000 | Points generated by all lasers per second |
|
||||
| `rotation_frequency` | float | 10.0 | Lidar rotation frequency |
|
||||
| `upper_fov` | float | 10.0 | Angle in degrees of the upper most laser |
|
||||
|
@ -322,7 +322,7 @@ objects.
|
|||
| `frame` | int | Frame number when the measurement took place |
|
||||
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the episode |
|
||||
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
|
||||
| `horizontal_angle` | float | Angle in XY plane of the lidar this frame (in degrees) |
|
||||
| `horizontal_angle` | float | Angle in XY plane of the lidar this frame (in radians) |
|
||||
| `channels` | int | Number of channels (lasers) of the lidar |
|
||||
| `get_point_count(channel)` | int | Number of points per channel captured this frame |
|
||||
| `raw_data` | bytes | Array of 32-bits floats (XYZ of each point) |
|
||||
|
@ -457,3 +457,23 @@ objects.
|
|||
| `actor` | carla.Actor | Actor that detected the obstacle ("self" actor) |
|
||||
| `other_actor` | carla.Actor | Actor detected as obstacle |
|
||||
| `distance` | float | Distance from actor to other_actor |
|
||||
|
||||
sensor.other.imu
|
||||
----------------
|
||||
|
||||
This sensor, when attached to an actor, the user can access to it's accelerometer, gyroscope and compass.
|
||||
|
||||
<h4>Output attributes</h4>
|
||||
|
||||
This sensor produces
|
||||
[`carla.IMUMeasurement`](python_api.md#carla.IMUMeasurement)
|
||||
objects.
|
||||
|
||||
| Sensor data attribute | Type | Description |
|
||||
| --------------------- | --------------- | ----------- |
|
||||
| `frame` | int | Frame number when the measurement took place |
|
||||
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the episode |
|
||||
| `transform` | carla.Transform | Transform in world |
|
||||
| `accelerometer` | carla.Vector3D | Measures linear acceleration in `m/s^2` |
|
||||
| `gyroscope` | carla.Vector3D | Measures angular velocity in `rad/sec` |
|
||||
| `compass` | float | Orientation with respect to the North (`(0.0, -1.0, 0.0)` in Unreal) in radians |
|
||||
|
|
|
@ -1317,19 +1317,35 @@ Return number of [carla.ActorSnapshot](#carla.ActorSnapshot) present in this [ca
|
|||
|
||||
---
|
||||
|
||||
## carla.GnssEvent<a name="carla.GnssEvent"></a><sub><sup>([carla.SensorData](#carla.SensorData))</sup></sub> <sub><sup>_class_</sup></sub>
|
||||
## carla.GnssMeasurement<a name="carla.GnssMeasurement"></a><sub><sup>([carla.SensorData](#carla.SensorData))</sup></sub> <sub><sup>_class_</sup></sub>
|
||||
Gnss sensor data.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.GnssEvent.latitude"></a>**<font color="#f8805a">latitude</font>** (_float_)
|
||||
- <a name="carla.GnssMeasurement.latitude"></a>**<font color="#f8805a">latitude</font>** (_float_)
|
||||
North/South value of a point on the map.
|
||||
- <a name="carla.GnssEvent.longitude"></a>**<font color="#f8805a">longitude</font>** (_float_)
|
||||
- <a name="carla.GnssMeasurement.longitude"></a>**<font color="#f8805a">longitude</font>** (_float_)
|
||||
West/East value of a point on the map.
|
||||
- <a name="carla.GnssEvent.altitude"></a>**<font color="#f8805a">altitude</font>** (_float_)
|
||||
- <a name="carla.GnssMeasurement.altitude"></a>**<font color="#f8805a">altitude</font>** (_float_)
|
||||
Height regarding ground level.
|
||||
|
||||
<h3>Methods</h3>
|
||||
- <a name="carla.GnssEvent.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
- <a name="carla.GnssMeasurement.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
||||
## carla.IMUMeasurement<a name="carla.IMUMeasurement"></a><sub><sup>([carla.SensorData](#carla.SensorData))</sup></sub> <sub><sup>_class_</sup></sub>
|
||||
IMU sensor data regarding the sensor World's transformation.
|
||||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.IMUMeasurement.accelerometer"></a>**<font color="#f8805a">accelerometer</font>** (_[carla.Vector3D](#carla.Vector3D)_)
|
||||
Measures linear acceleration in `m/s^2`.
|
||||
- <a name="carla.IMUMeasurement.gyroscope"></a>**<font color="#f8805a">gyroscope</font>** (_[carla.Vector3D](#carla.Vector3D)_)
|
||||
Measures angular velocity in `rad/sec`.
|
||||
- <a name="carla.IMUMeasurement.compass"></a>**<font color="#f8805a">compass</font>** (_float_)
|
||||
Orientation with respect to the North (`(0.0, -1.0, 0.0)` in Unreal) in radians.
|
||||
|
||||
<h3>Methods</h3>
|
||||
- <a name="carla.IMUMeasurement.__str__"></a>**<font color="#7fb800">\__str__</font>**(<font color="#00a6ed">**self**</font>)
|
||||
|
||||
---
|
||||
|
||||
|
@ -1387,7 +1403,7 @@ Lidar sensor measurement data.
|
|||
|
||||
<h3>Instance Variables</h3>
|
||||
- <a name="carla.LidarMeasurement.horizontal_angle"></a>**<font color="#f8805a">horizontal_angle</font>** (_float_)
|
||||
Horizontal angle that the Lidar has rotated at the time of the measurement.
|
||||
Horizontal angle that the Lidar has rotated at the time of the measurement (in radians).
|
||||
- <a name="carla.LidarMeasurement.channels"></a>**<font color="#f8805a">channels</font>** (_int_)
|
||||
Number of lasers.
|
||||
- <a name="carla.LidarMeasurement.raw_data"></a>**<font color="#f8805a">raw_data</font>** (_bytes_)
|
||||
|
|
|
@ -27,6 +27,12 @@ namespace geom {
|
|||
return static_cast<T>(3.14159265358979323846264338327950288);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static constexpr T Pi2() {
|
||||
static_assert(std::is_floating_point<T>::value, "type must be floating point");
|
||||
return static_cast<T>(static_cast<T>(2) * Pi<T>());
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static constexpr T ToDegrees(T rad) {
|
||||
static_assert(std::is_floating_point<T>::value, "type must be floating point");
|
||||
|
|
|
@ -137,6 +137,12 @@ namespace geom {
|
|||
|
||||
#ifdef LIBCARLA_INCLUDED_FROM_UE4
|
||||
|
||||
/// These 2 methods are explicitly deleted to avoid creating them by other users,
|
||||
/// unlike locations, some vectors have units and some don't, by removing
|
||||
/// these methods we found several places were the conversion from cm to m was missing
|
||||
Vector3D(const FVector &v) = delete;
|
||||
Vector3D& operator=(const FVector &rhs) = delete;
|
||||
|
||||
/// Return a Vector3D converted from centimeters to meters.
|
||||
Vector3D ToMeters() const {
|
||||
return *this * 1e-2f;
|
||||
|
|
|
@ -14,7 +14,7 @@ namespace pointcloud {
|
|||
void PointCloudIO::WriteHeader(std::ostream &out, size_t number_of_points) {
|
||||
out << "ply\n"
|
||||
"format ascii 1.0\n"
|
||||
"element vertex " << number_of_points << "\n"
|
||||
"element vertex " << std::to_string(number_of_points) << "\n"
|
||||
"property float32 x\n"
|
||||
"property float32 y\n"
|
||||
"property float32 z\n"
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
#include "carla/sensor/s11n/CollisionEventSerializer.h"
|
||||
#include "carla/sensor/s11n/EpisodeStateSerializer.h"
|
||||
#include "carla/sensor/s11n/ImageSerializer.h"
|
||||
#include "carla/sensor/s11n/IMUSerializer.h"
|
||||
#include "carla/sensor/s11n/LidarSerializer.h"
|
||||
#include "carla/sensor/s11n/NoopSerializer.h"
|
||||
#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h"
|
||||
|
@ -25,6 +26,7 @@
|
|||
class ACollisionSensor;
|
||||
class ADepthCamera;
|
||||
class AGnssSensor;
|
||||
class AInertialMeasurementUnit;
|
||||
class ALaneInvasionSensor;
|
||||
class AObstacleDetectionSensor;
|
||||
class ARayCastLidar;
|
||||
|
@ -46,6 +48,7 @@ namespace sensor {
|
|||
std::pair<FWorldObserver *, s11n::EpisodeStateSerializer>,
|
||||
std::pair<ASceneCaptureCamera *, s11n::ImageSerializer>,
|
||||
std::pair<ADepthCamera *, s11n::ImageSerializer>,
|
||||
std::pair<AInertialMeasurementUnit *, s11n::IMUSerializer>,
|
||||
std::pair<ASemanticSegmentationCamera *, s11n::ImageSerializer>,
|
||||
std::pair<ARayCastLidar *, s11n::LidarSerializer>,
|
||||
std::pair<ACollisionSensor *, s11n::CollisionEventSerializer>,
|
||||
|
@ -67,6 +70,7 @@ namespace sensor {
|
|||
#include "Carla/Sensor/RayCastLidar.h"
|
||||
#include "Carla/Sensor/SceneCaptureCamera.h"
|
||||
#include "Carla/Sensor/SemanticSegmentationCamera.h"
|
||||
#include "Carla/Sensor/InertialMeasurementUnit.h"
|
||||
#include "Carla/Sensor/WorldObserver.h"
|
||||
#include "Carla/Sensor/GnssSensor.h"
|
||||
#include "Carla/Sensor/LaneInvasionSensor.h"
|
||||
|
|
|
@ -17,7 +17,7 @@ namespace sensor {
|
|||
namespace data {
|
||||
|
||||
/// A registered collision.
|
||||
class CollisionEvent : public SensorData {
|
||||
class CollisionEvent : public SensorData {
|
||||
using Super = SensorData;
|
||||
protected:
|
||||
|
||||
|
|
|
@ -0,0 +1,56 @@
|
|||
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/geom/Vector3D.h"
|
||||
#include "carla/sensor/s11n/IMUSerializer.h"
|
||||
#include "carla/sensor/SensorData.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
class IMUMeasurement : public SensorData {
|
||||
protected:
|
||||
|
||||
using Super = SensorData;
|
||||
|
||||
using Serializer = s11n::IMUSerializer;
|
||||
|
||||
friend Serializer;
|
||||
|
||||
explicit IMUMeasurement(const RawData &data)
|
||||
: Super(data),
|
||||
_accelerometer(Serializer::DeserializeRawData(data).accelerometer),
|
||||
_gyroscope(Serializer::DeserializeRawData(data).gyroscope),
|
||||
_compass(Serializer::DeserializeRawData(data).compass) {}
|
||||
|
||||
public:
|
||||
|
||||
geom::Vector3D GetAccelerometer() const {
|
||||
return _accelerometer;
|
||||
}
|
||||
|
||||
geom::Vector3D GetGyroscope() const {
|
||||
return _gyroscope;
|
||||
}
|
||||
|
||||
float GetCompass() const {
|
||||
return _compass;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
geom::Vector3D _accelerometer;
|
||||
geom::Vector3D _gyroscope;
|
||||
float _compass;
|
||||
|
||||
};
|
||||
|
||||
} // namespace data
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,20 @@
|
|||
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/sensor/s11n/IMUSerializer.h"
|
||||
#include "carla/sensor/data/IMUMeasurement.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace s11n {
|
||||
|
||||
SharedPtr<SensorData> IMUSerializer::Deserialize(RawData &&data) {
|
||||
return SharedPtr<SensorData>(new data::IMUMeasurement(std::move(data)));
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
// #include "carla/Buffer.h"
|
||||
#include "carla/Memory.h"
|
||||
#include "carla/sensor/RawData.h"
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
|
||||
class SensorData;
|
||||
|
||||
namespace s11n {
|
||||
|
||||
class IMUSerializer
|
||||
{
|
||||
public:
|
||||
|
||||
struct Data {
|
||||
|
||||
geom::Vector3D accelerometer;
|
||||
|
||||
geom::Vector3D gyroscope;
|
||||
|
||||
float compass;
|
||||
|
||||
MSGPACK_DEFINE_ARRAY(accelerometer, gyroscope, compass)
|
||||
};
|
||||
|
||||
template <typename SensorT>
|
||||
static Buffer Serialize(
|
||||
const SensorT &sensor,
|
||||
const geom::Vector3D &accelerometer,
|
||||
const geom::Vector3D &gyroscope,
|
||||
const float compass);
|
||||
|
||||
static Data DeserializeRawData(const RawData &message) {
|
||||
return MsgPack::UnPack<Data>(message.begin(), message.size());
|
||||
}
|
||||
|
||||
static SharedPtr<SensorData> Deserialize(RawData &&data);
|
||||
};
|
||||
|
||||
template <typename SensorT>
|
||||
inline Buffer IMUSerializer::Serialize(
|
||||
const SensorT &,
|
||||
const geom::Vector3D &accelerometer,
|
||||
const geom::Vector3D &gyroscope,
|
||||
const float compass) {
|
||||
return MsgPack::Pack(Data{accelerometer, gyroscope, compass});
|
||||
}
|
||||
|
||||
} // namespace s11n
|
||||
} // namespace sensor
|
||||
} // namespace carla
|
|
@ -11,6 +11,7 @@
|
|||
#include <carla/pointcloud/PointCloudIO.h>
|
||||
#include <carla/sensor/SensorData.h>
|
||||
#include <carla/sensor/data/CollisionEvent.h>
|
||||
#include <carla/sensor/data/IMUMeasurement.h>
|
||||
#include <carla/sensor/data/ObstacleDetectionEvent.h>
|
||||
#include <carla/sensor/data/Image.h>
|
||||
#include <carla/sensor/data/LaneInvasionEvent.h>
|
||||
|
@ -27,50 +28,60 @@ namespace sensor {
|
|||
namespace data {
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const Image &image) {
|
||||
out << "Image(frame=" << image.GetFrame()
|
||||
<< ", timestamp=" << image.GetTimestamp()
|
||||
<< ", size=" << image.GetWidth() << 'x' << image.GetHeight()
|
||||
out << "Image(frame=" << std::to_string(image.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(image.GetTimestamp())
|
||||
<< ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight())
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) {
|
||||
out << "LidarMeasurement(frame=" << meas.GetFrame()
|
||||
<< ", timestamp=" << meas.GetTimestamp()
|
||||
<< ", number_of_points=" << meas.size()
|
||||
out << "LidarMeasurement(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ", number_of_points=" << std::to_string(meas.size())
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) {
|
||||
out << "CollisionEvent(frame=" << meas.GetFrame()
|
||||
<< ", timestamp=" << meas.GetTimestamp()
|
||||
out << "CollisionEvent(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ", other_actor=" << meas.GetOtherActor()
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) {
|
||||
out << "ObstacleDetectionEvent(frame=" << meas.GetFrame()
|
||||
<< ", timestamp=" << meas.GetTimestamp()
|
||||
out << "ObstacleDetectionEvent(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ", other_actor=" << meas.GetOtherActor()
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) {
|
||||
out << "LaneInvasionEvent(frame=" << meas.GetFrame()
|
||||
<< ", timestamp=" << meas.GetTimestamp()
|
||||
out << "LaneInvasionEvent(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const GnssEvent &meas) {
|
||||
out << "GnssEvent(frame=" << meas.GetFrame()
|
||||
<< ", timestamp=" << meas.GetTimestamp()
|
||||
<< ", lat=" << meas.GetLatitude()
|
||||
<< ", lon=" << meas.GetLongitude()
|
||||
<< ", alt=" << meas.GetAltitude()
|
||||
out << "GnssEvent(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ", lat=" << std::to_string(meas.GetLatitude())
|
||||
<< ", lon=" << std::to_string(meas.GetLongitude())
|
||||
<< ", alt=" << std::to_string(meas.GetAltitude())
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const IMUMeasurement &meas) {
|
||||
out << "IMUMeasurement(frame=" << std::to_string(meas.GetFrame())
|
||||
<< ", timestamp=" << std::to_string(meas.GetTimestamp())
|
||||
<< ", accelerometer=" << meas.GetAccelerometer()
|
||||
<< ", gyroscope=" << meas.GetGyroscope()
|
||||
<< ", compass=" << std::to_string(meas.GetCompass())
|
||||
<< ')';
|
||||
return out;
|
||||
}
|
||||
|
@ -235,4 +246,11 @@ void export_sensor_data() {
|
|||
.add_property("altitude", &csd::GnssEvent::GetAltitude)
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
|
||||
class_<csd::IMUMeasurement, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::IMUMeasurement>>("IMUMeasurement", no_init)
|
||||
.add_property("accelerometer", &csd::IMUMeasurement::GetAccelerometer)
|
||||
.add_property("gyroscope", &csd::IMUMeasurement::GetGyroscope)
|
||||
.add_property("compass", &csd::IMUMeasurement::GetCompass)
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
}
|
||||
|
|
|
@ -115,7 +115,7 @@
|
|||
- var_name: horizontal_angle
|
||||
type: float
|
||||
doc: >
|
||||
Horizontal angle that the Lidar has rotated at the time of the measurement
|
||||
Horizontal angle that the Lidar has rotated at the time of the measurement (in radians)
|
||||
- var_name: channels
|
||||
type: int
|
||||
doc: >
|
||||
|
@ -128,7 +128,7 @@
|
|||
methods:
|
||||
- def_name: get_point_count
|
||||
params:
|
||||
- param_name: channel
|
||||
- param_name: channel
|
||||
type: int
|
||||
doc: >
|
||||
Retrieve the number of points that are generated by this channel.
|
||||
|
@ -138,7 +138,7 @@
|
|||
# --------------------------------------
|
||||
- def_name: save_to_disk
|
||||
params:
|
||||
- param_name: path
|
||||
- param_name: path
|
||||
type: str
|
||||
doc: >
|
||||
Save point cloud to disk
|
||||
|
@ -209,7 +209,7 @@
|
|||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: __str__
|
||||
doc: >
|
||||
doc: >
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: LaneInvasionEvent
|
||||
|
@ -230,10 +230,10 @@
|
|||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: __str__
|
||||
doc: >
|
||||
doc: >
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: GnssEvent
|
||||
- class_name: GnssMeasurement
|
||||
parent: carla.SensorData
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
|
@ -243,11 +243,11 @@
|
|||
- var_name: latitude
|
||||
type: float
|
||||
doc: >
|
||||
North/South value of a point on the map.
|
||||
North/South value of a point on the map.
|
||||
- var_name: longitude
|
||||
type: float
|
||||
doc: >
|
||||
West/East value of a point on the map.
|
||||
West/East value of a point on the map.
|
||||
- var_name: altitude
|
||||
type: float
|
||||
doc: >
|
||||
|
@ -255,6 +255,31 @@
|
|||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: __str__
|
||||
doc: >
|
||||
doc: >
|
||||
# --------------------------------------
|
||||
|
||||
- class_name: IMUMeasurement
|
||||
parent: carla.SensorData
|
||||
# - DESCRIPTION ------------------------
|
||||
doc: >
|
||||
IMU sensor data regarding the sensor World's transformation
|
||||
# - PROPERTIES -------------------------
|
||||
instance_variables:
|
||||
- var_name: accelerometer
|
||||
type: carla.Vector3D
|
||||
doc: >
|
||||
Measures linear acceleration in `m/s^2`.
|
||||
- var_name: gyroscope
|
||||
type: carla.Vector3D
|
||||
doc: >
|
||||
Measures angular velocity in `rad/sec`.
|
||||
- var_name: compass
|
||||
type: float
|
||||
doc: >
|
||||
Orientation with respect to the North (`(0.0, -1.0, 0.0)` in Unreal) in radians.
|
||||
# - METHODS ----------------------------
|
||||
methods:
|
||||
- def_name: __str__
|
||||
doc: >
|
||||
# --------------------------------------
|
||||
...
|
||||
|
|
|
@ -649,7 +649,7 @@ class CameraManager(object):
|
|||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
bp.set_attribute('image_size_y', str(hud.dim[1]))
|
||||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
bp.set_attribute('range', '50')
|
||||
item.append(bp)
|
||||
self.index = None
|
||||
|
||||
|
|
|
@ -718,7 +718,7 @@ class CameraManager(object):
|
|||
for attr_name, attr_value in item[3].items():
|
||||
bp.set_attribute(attr_name, attr_value)
|
||||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
bp.set_attribute('range', '50')
|
||||
item.append(bp)
|
||||
self.index = None
|
||||
|
||||
|
|
|
@ -694,7 +694,7 @@ class CameraManager(object):
|
|||
bp.set_attribute('image_size_x', str(hud.dim[0]))
|
||||
bp.set_attribute('image_size_y', str(hud.dim[1]))
|
||||
elif item[0].startswith('sensor.lidar'):
|
||||
bp.set_attribute('range', '5000')
|
||||
bp.set_attribute('range', '50')
|
||||
item.append(bp)
|
||||
self.index = None
|
||||
|
||||
|
|
|
@ -44,7 +44,7 @@ def draw_transform(debug, trans, col=carla.Color(255, 0, 0), lt=-1):
|
|||
x=trans.location.x + math.cos(pitch_in_rad) * math.cos(yaw_in_rad),
|
||||
y=trans.location.y + math.cos(pitch_in_rad) * math.sin(yaw_in_rad),
|
||||
z=trans.location.z + math.sin(pitch_in_rad))
|
||||
debug.draw_arrow(trans.location, p1, thickness=0.05, arrow_size=1.0, color=col, life_time=lt)
|
||||
debug.draw_arrow(trans.location, p1, thickness=0.05, arrow_size=0.1, color=col, life_time=lt)
|
||||
|
||||
|
||||
def draw_waypoint_union(debug, w0, w1, color=carla.Color(255, 0, 0), lt=5):
|
||||
|
@ -75,6 +75,10 @@ def main():
|
|||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-i', '--info',
|
||||
action='store_true',
|
||||
help='Show text information')
|
||||
argparser.add_argument(
|
||||
'-x',
|
||||
default=0.0,
|
||||
|
@ -142,13 +146,13 @@ def main():
|
|||
potential_w.remove(next_w)
|
||||
|
||||
# Render some nice information, notice that you can't see the strings if you are using an editor camera
|
||||
draw_waypoint_info(debug, current_w, trail_life_time)
|
||||
if args.info:
|
||||
draw_waypoint_info(debug, current_w, trail_life_time)
|
||||
draw_waypoint_union(debug, current_w, next_w, cyan if current_w.is_junction else green, trail_life_time)
|
||||
draw_transform(debug, current_w.transform, white, trail_life_time)
|
||||
|
||||
# print the remaining waypoints
|
||||
for p in potential_w:
|
||||
debug.draw_string(p.transform.location, str(p.lane_id), False, orange, trail_life_time)
|
||||
draw_waypoint_union(debug, current_w, p, red, trail_life_time)
|
||||
draw_transform(debug, p.transform, white, trail_life_time)
|
||||
|
||||
|
|
|
@ -657,7 +657,7 @@ void UActorBlueprintFunctionLibrary::MakeLidarDefinition(
|
|||
FActorVariation Range;
|
||||
Range.Id = TEXT("range");
|
||||
Range.Type = EActorAttributeType::Float;
|
||||
Range.RecommendedValues = { TEXT("1000.0") };
|
||||
Range.RecommendedValues = { TEXT("10.0") }; // 10 meters
|
||||
// Points per second.
|
||||
FActorVariation PointsPerSecond;
|
||||
PointsPerSecond.Id = TEXT("points_per_second");
|
||||
|
@ -1188,10 +1188,11 @@ void UActorBlueprintFunctionLibrary::SetLidar(
|
|||
const FActorDescription &Description,
|
||||
FLidarDescription &Lidar)
|
||||
{
|
||||
constexpr float TO_CENTIMETERS = 1e2;
|
||||
Lidar.Channels =
|
||||
RetrieveActorAttributeToInt("channels", Description.Variations, Lidar.Channels);
|
||||
Lidar.Range =
|
||||
RetrieveActorAttributeToFloat("range", Description.Variations, Lidar.Range);
|
||||
RetrieveActorAttributeToFloat("range", Description.Variations, 10.0f) * TO_CENTIMETERS;
|
||||
Lidar.PointsPerSecond =
|
||||
RetrieveActorAttributeToInt("points_per_second", Description.Variations, Lidar.PointsPerSecond);
|
||||
Lidar.RotationFrequency =
|
||||
|
|
|
@ -17,7 +17,8 @@ public:
|
|||
|
||||
using IdType = uint32;
|
||||
|
||||
enum class ActorType : uint8 {
|
||||
enum class ActorType : uint8
|
||||
{
|
||||
Other,
|
||||
Vehicle,
|
||||
Walker,
|
||||
|
|
|
@ -0,0 +1,130 @@
|
|||
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "Carla.h"
|
||||
#include "InertialMeasurementUnit.h"
|
||||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include "carla/geom/Math.h"
|
||||
#include "carla/geom/Vector3D.h"
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
#include "Carla/Vehicle/CarlaWheeledVehicle.h"
|
||||
#include "Carla/Sensor/WorldObserver.h"
|
||||
#include "Carla/Actor/ActorBlueprintFunctionLibrary.h"
|
||||
|
||||
// Based on OpenDRIVE's lon and lat
|
||||
const FVector AInertialMeasurementUnit::CarlaNorthVector =
|
||||
FVector(0.0f, -1.0f, 0.0f);
|
||||
|
||||
AInertialMeasurementUnit::AInertialMeasurementUnit(
|
||||
const FObjectInitializer &ObjectInitializer)
|
||||
: Super(ObjectInitializer)
|
||||
{
|
||||
PrimaryActorTick.bCanEverTick = true;
|
||||
PrimaryActorTick.TickGroup = TG_PostPhysics;
|
||||
}
|
||||
|
||||
FActorDefinition AInertialMeasurementUnit::GetSensorDefinition()
|
||||
{
|
||||
return UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(
|
||||
TEXT("other"),
|
||||
TEXT("imu"));
|
||||
}
|
||||
|
||||
void AInertialMeasurementUnit::Set(const FActorDescription &ActorDescription)
|
||||
{
|
||||
Super::Set(ActorDescription);
|
||||
// Fill the parameters that the user requested
|
||||
// Not currently needed in this sensor
|
||||
}
|
||||
|
||||
void AInertialMeasurementUnit::SetOwner(AActor *Owner)
|
||||
{
|
||||
Super::SetOwner(Owner);
|
||||
}
|
||||
|
||||
// Copy of FWorldObserver_GetAngularVelocity but using radiants
|
||||
static FVector carla_GetActorAngularVelocityInRadians(AActor &Actor)
|
||||
{
|
||||
const auto RootComponent = Cast<UPrimitiveComponent>(Actor.GetRootComponent());
|
||||
const FVector AngularVelocity =
|
||||
RootComponent != nullptr ?
|
||||
RootComponent->GetPhysicsAngularVelocityInRadians() :
|
||||
FVector { 0.0f, 0.0f, 0.0f };
|
||||
|
||||
return AngularVelocity;
|
||||
}
|
||||
|
||||
void AInertialMeasurementUnit::Tick(float DeltaTime)
|
||||
{
|
||||
Super::Tick(DeltaTime);
|
||||
|
||||
namespace cg = carla::geom;
|
||||
|
||||
// Accelerometer measures linear acceleration in m/s2
|
||||
constexpr float TO_METERS = 1e-2;
|
||||
|
||||
ACarlaWheeledVehicle *vehicle = Cast<ACarlaWheeledVehicle>(GetOwner());
|
||||
const FVector CurrentVelocity = vehicle->GetVehicleForwardSpeed() * vehicle->GetVehicleOrientation();
|
||||
float CurrentSimulationTime = GetWorld()->GetTimeSeconds();
|
||||
FVector FVectorAccelerometer =
|
||||
TO_METERS * (CurrentVelocity - PrevVelocity) / DeltaTime;
|
||||
|
||||
PrevVelocity = CurrentVelocity;
|
||||
|
||||
FQuat ImuRotation = GetRootComponent()->GetComponentTransform().GetRotation();
|
||||
FVectorAccelerometer = ImuRotation.UnrotateVector(FVectorAccelerometer);
|
||||
|
||||
// Cast from FVector to our Vector3D to correctly send the data in m/s2
|
||||
const cg::Vector3D Accelerometer (
|
||||
FVectorAccelerometer.X,
|
||||
FVectorAccelerometer.Y,
|
||||
FVectorAccelerometer.Z
|
||||
);
|
||||
|
||||
// Gyroscope measures angular velocity in rad/sec
|
||||
const FVector AngularVelocity =
|
||||
carla_GetActorAngularVelocityInRadians(*GetOwner());
|
||||
|
||||
const FQuat SensorLocalRotation =
|
||||
RootComponent->GetRelativeTransform().GetRotation();
|
||||
|
||||
const FVector FVectorGyroscope =
|
||||
SensorLocalRotation.RotateVector(AngularVelocity);
|
||||
|
||||
// Cast from FVector to our Vector3D to correctly send the data in rad/s
|
||||
const cg::Vector3D Gyroscope (
|
||||
FVectorGyroscope.X,
|
||||
FVectorGyroscope.Y,
|
||||
FVectorGyroscope.Z
|
||||
);
|
||||
|
||||
// Magnetometer: orientation with respect to the North in rad
|
||||
const FVector ForwVect = GetActorForwardVector().GetSafeNormal2D();
|
||||
float Compass = std::acos(FVector::DotProduct(CarlaNorthVector, ForwVect));
|
||||
|
||||
// Keep the angle between [0, 2pi)
|
||||
if (FVector::CrossProduct(CarlaNorthVector, ForwVect).Z > 0.0f)
|
||||
{
|
||||
Compass = cg::Math::Pi2<float>() - Compass;
|
||||
}
|
||||
|
||||
auto Stream = GetDataStream(*this);
|
||||
Stream.Send(
|
||||
*this,
|
||||
Accelerometer,
|
||||
Gyroscope,
|
||||
Compass);
|
||||
}
|
||||
|
||||
void AInertialMeasurementUnit::BeginPlay()
|
||||
{
|
||||
Super::BeginPlay();
|
||||
|
||||
constexpr float TO_METERS = 1e-2;
|
||||
PrevVelocity = GetOwner()->GetVelocity();
|
||||
}
|
|
@ -0,0 +1,42 @@
|
|||
// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Carla/Sensor/Sensor.h"
|
||||
|
||||
#include "Carla/Actor/ActorDefinition.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
#include "InertialMeasurementUnit.generated.h"
|
||||
|
||||
UCLASS()
|
||||
class CARLA_API AInertialMeasurementUnit : public ASensor
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
public:
|
||||
|
||||
AInertialMeasurementUnit(const FObjectInitializer &ObjectInitializer);
|
||||
|
||||
static FActorDefinition GetSensorDefinition();
|
||||
|
||||
void Set(const FActorDescription &ActorDescription) override;
|
||||
|
||||
void SetOwner(AActor *Owner) override;
|
||||
|
||||
void Tick(float DeltaTime) override;
|
||||
|
||||
/// Based on OpenDRIVE's lon and lat, North is in (0.0f, -1.0f, 0.0f)
|
||||
static const FVector CarlaNorthVector;
|
||||
|
||||
private:
|
||||
|
||||
void BeginPlay() override;
|
||||
|
||||
FVector PrevVelocity;
|
||||
|
||||
};
|
|
@ -19,7 +19,7 @@ struct CARLA_API FLidarDescription
|
|||
|
||||
/// Measure distance in centimeters.
|
||||
UPROPERTY(EditAnywhere)
|
||||
float Range = 5000.0f;
|
||||
float Range = 1000.0f;
|
||||
|
||||
/// Points generated by all lasers per second.
|
||||
UPROPERTY(EditAnywhere)
|
||||
|
|
|
@ -6,9 +6,12 @@
|
|||
|
||||
#include "Carla.h"
|
||||
#include "Carla/Sensor/RayCastLidar.h"
|
||||
|
||||
#include "Carla/Actor/ActorBlueprintFunctionLibrary.h"
|
||||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include "carla/geom/Math.h"
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
#include "DrawDebugHelpers.h"
|
||||
#include "Engine/CollisionProfile.h"
|
||||
#include "Runtime/Engine/Classes/Kismet/KismetMathLibrary.h"
|
||||
|
@ -84,7 +87,8 @@ void ARayCastLidar::ReadPoints(const float DeltaTime)
|
|||
|
||||
check(ChannelCount == LaserAngles.Num());
|
||||
|
||||
const float CurrentHorizontalAngle = LidarMeasurement.GetHorizontalAngle();
|
||||
const float CurrentHorizontalAngle = carla::geom::Math::ToDegrees(
|
||||
LidarMeasurement.GetHorizontalAngle());
|
||||
const float AngleDistanceOfTick = Description.RotationFrequency * 360.0f * DeltaTime;
|
||||
const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneLaser;
|
||||
|
||||
|
@ -103,7 +107,8 @@ void ARayCastLidar::ReadPoints(const float DeltaTime)
|
|||
}
|
||||
}
|
||||
|
||||
const float HorizontalAngle = std::fmod(CurrentHorizontalAngle + AngleDistanceOfTick, 360.0f);
|
||||
const float HorizontalAngle = carla::geom::Math::ToRadians(
|
||||
std::fmod(CurrentHorizontalAngle + AngleDistanceOfTick, 360.0f));
|
||||
LidarMeasurement.SetHorizontalAngle(HorizontalAngle);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue