Merge branch 'dev' into lidar
This commit is contained in:
commit
e3960046f7
|
@ -0,0 +1,13 @@
|
|||
language: python
|
||||
|
||||
python:
|
||||
- "2.7"
|
||||
- "3.5"
|
||||
- "3.6"
|
||||
|
||||
install:
|
||||
- pip install -r PythonClient/requirements.txt
|
||||
- pip install pylint
|
||||
|
||||
script:
|
||||
- pylint --errors-only --rcfile=PythonClient/.pylintrc PythonClient/carla PythonClient/*.py
|
|
@ -37,9 +37,13 @@ autopilot_control | Control | Vehicle's autopilot control that would
|
|||
|
||||
###### Transform
|
||||
|
||||
The transform contains two Vector3D objects, location and orientation.
|
||||
Currently, the orientation is represented as the Cartesian coordinates X, Y, Z.
|
||||
_We will probably change this in the future to Roll, Pitch, and Yaw._
|
||||
The transform contains the location and rotation of the player.
|
||||
|
||||
Key | Type | Description
|
||||
-------------------------- | ---------- | ------------
|
||||
location | Vector3D | World location.
|
||||
orientation *[deprecated]* | Vector3D | Orientation in Cartesian coordinates.
|
||||
rotation | Rotation3D | Pitch, roll, and yaw.
|
||||
|
||||
###### Collision
|
||||
|
||||
|
|
|
@ -0,0 +1,3 @@
|
|||
[TYPECHECK]
|
||||
ignored-modules=ConfigParser,numpy,pygame,shutil
|
||||
ignored-classes=_socketobject
|
|
@ -19,7 +19,7 @@ DESCRIPTOR = _descriptor.FileDescriptor(
|
|||
name='carla_server.proto',
|
||||
package='carla_server',
|
||||
syntax='proto3',
|
||||
serialized_pb=_b('\n\x12\x63\x61rla_server.proto\x12\x0c\x63\x61rla_server\"+\n\x08Vector3D\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"b\n\tTransform\x12(\n\x08location\x18\x01 \x01(\x0b\x32\x16.carla_server.Vector3D\x12+\n\x0borientation\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\"x\n\x07Vehicle\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"{\n\nPedestrian\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x94\x01\n\x0cTrafficLight\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x05state\x18\x02 \x01(\x0e\x32 .carla_server.TrafficLight.State\"\'\n\x05State\x12\t\n\x05GREEN\x10\x00\x12\n\n\x06YELLOW\x10\x01\x12\x07\n\x03RED\x10\x02\"Q\n\x0eSpeedLimitSign\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12\x13\n\x0bspeed_limit\x18\x02 \x01(\x02\"\xe5\x01\n\x05\x41gent\x12\n\n\x02id\x18\x01 \x01(\x07\x12(\n\x07vehicle\x18\x02 \x01(\x0b\x32\x15.carla_server.VehicleH\x00\x12.\n\npedestrian\x18\x03 \x01(\x0b\x32\x18.carla_server.PedestrianH\x00\x12\x33\n\rtraffic_light\x18\x04 \x01(\x0b\x32\x1a.carla_server.TrafficLightH\x00\x12\x38\n\x10speed_limit_sign\x18\x05 \x01(\x0b\x32\x1c.carla_server.SpeedLimitSignH\x00\x42\x07\n\x05\x61gent\"%\n\x11RequestNewEpisode\x12\x10\n\x08ini_file\x18\x01 \x01(\t\"G\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\"/\n\x0c\x45pisodeStart\x12\x1f\n\x17player_start_spot_index\x18\x01 \x01(\r\"\x1d\n\x0c\x45pisodeReady\x12\r\n\x05ready\x18\x01 \x01(\x08\"^\n\x07\x43ontrol\x12\r\n\x05steer\x18\x01 \x01(\x02\x12\x10\n\x08throttle\x18\x02 \x01(\x02\x12\r\n\x05\x62rake\x18\x03 \x01(\x02\x12\x12\n\nhand_brake\x18\x04 \x01(\x08\x12\x0f\n\x07reverse\x18\x05 \x01(\x08\"\x8a\x04\n\x0cMeasurements\x12\x1a\n\x12platform_timestamp\x18\x01 \x01(\r\x12\x16\n\x0egame_timestamp\x18\x02 \x01(\r\x12J\n\x13player_measurements\x18\x03 \x01(\x0b\x32-.carla_server.Measurements.PlayerMeasurements\x12.\n\x11non_player_agents\x18\x04 \x03(\x0b\x32\x13.carla_server.Agent\x1a\xc9\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12,\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x04 \x01(\x02\x12\x1a\n\x12\x63ollision_vehicles\x18\x05 \x01(\x02\x12\x1d\n\x15\x63ollision_pedestrians\x18\x06 \x01(\x02\x12\x17\n\x0f\x63ollision_other\x18\x07 \x01(\x02\x12\x1e\n\x16intersection_otherlane\x18\x08 \x01(\x02\x12\x1c\n\x14intersection_offroad\x18\t \x01(\x02\x12\x30\n\x11\x61utopilot_control\x18\n \x01(\x0b\x32\x15.carla_server.ControlB\x03\xf8\x01\x01\x62\x06proto3')
|
||||
serialized_pb=_b('\n\x12\x63\x61rla_server.proto\x12\x0c\x63\x61rla_server\"+\n\x08Vector3D\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"6\n\nRotation3D\x12\r\n\x05pitch\x18\x01 \x01(\x02\x12\x0b\n\x03yaw\x18\x02 \x01(\x02\x12\x0c\n\x04roll\x18\x03 \x01(\x02\"\x92\x01\n\tTransform\x12(\n\x08location\x18\x01 \x01(\x0b\x32\x16.carla_server.Vector3D\x12/\n\x0borientation\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3DB\x02\x18\x01\x12*\n\x08rotation\x18\x03 \x01(\x0b\x32\x18.carla_server.Rotation3D\"x\n\x07Vehicle\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"{\n\nPedestrian\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x94\x01\n\x0cTrafficLight\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x05state\x18\x02 \x01(\x0e\x32 .carla_server.TrafficLight.State\"\'\n\x05State\x12\t\n\x05GREEN\x10\x00\x12\n\n\x06YELLOW\x10\x01\x12\x07\n\x03RED\x10\x02\"Q\n\x0eSpeedLimitSign\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12\x13\n\x0bspeed_limit\x18\x02 \x01(\x02\"\xe5\x01\n\x05\x41gent\x12\n\n\x02id\x18\x01 \x01(\x07\x12(\n\x07vehicle\x18\x02 \x01(\x0b\x32\x15.carla_server.VehicleH\x00\x12.\n\npedestrian\x18\x03 \x01(\x0b\x32\x18.carla_server.PedestrianH\x00\x12\x33\n\rtraffic_light\x18\x04 \x01(\x0b\x32\x1a.carla_server.TrafficLightH\x00\x12\x38\n\x10speed_limit_sign\x18\x05 \x01(\x0b\x32\x1c.carla_server.SpeedLimitSignH\x00\x42\x07\n\x05\x61gent\"%\n\x11RequestNewEpisode\x12\x10\n\x08ini_file\x18\x01 \x01(\t\"G\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\"/\n\x0c\x45pisodeStart\x12\x1f\n\x17player_start_spot_index\x18\x01 \x01(\r\"\x1d\n\x0c\x45pisodeReady\x12\r\n\x05ready\x18\x01 \x01(\x08\"^\n\x07\x43ontrol\x12\r\n\x05steer\x18\x01 \x01(\x02\x12\x10\n\x08throttle\x18\x02 \x01(\x02\x12\r\n\x05\x62rake\x18\x03 \x01(\x02\x12\x12\n\nhand_brake\x18\x04 \x01(\x08\x12\x0f\n\x07reverse\x18\x05 \x01(\x08\"\x8a\x04\n\x0cMeasurements\x12\x1a\n\x12platform_timestamp\x18\x01 \x01(\r\x12\x16\n\x0egame_timestamp\x18\x02 \x01(\r\x12J\n\x13player_measurements\x18\x03 \x01(\x0b\x32-.carla_server.Measurements.PlayerMeasurements\x12.\n\x11non_player_agents\x18\x04 \x03(\x0b\x32\x13.carla_server.Agent\x1a\xc9\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12,\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x04 \x01(\x02\x12\x1a\n\x12\x63ollision_vehicles\x18\x05 \x01(\x02\x12\x1d\n\x15\x63ollision_pedestrians\x18\x06 \x01(\x02\x12\x17\n\x0f\x63ollision_other\x18\x07 \x01(\x02\x12\x1e\n\x16intersection_otherlane\x18\x08 \x01(\x02\x12\x1c\n\x14intersection_offroad\x18\t \x01(\x02\x12\x30\n\x11\x61utopilot_control\x18\n \x01(\x0b\x32\x15.carla_server.ControlB\x03\xf8\x01\x01\x62\x06proto3')
|
||||
)
|
||||
|
||||
|
||||
|
@ -45,8 +45,8 @@ _TRAFFICLIGHT_STATE = _descriptor.EnumDescriptor(
|
|||
],
|
||||
containing_type=None,
|
||||
options=None,
|
||||
serialized_start=538,
|
||||
serialized_end=577,
|
||||
serialized_start=643,
|
||||
serialized_end=682,
|
||||
)
|
||||
_sym_db.RegisterEnumDescriptor(_TRAFFICLIGHT_STATE)
|
||||
|
||||
|
@ -96,6 +96,51 @@ _VECTOR3D = _descriptor.Descriptor(
|
|||
)
|
||||
|
||||
|
||||
_ROTATION3D = _descriptor.Descriptor(
|
||||
name='Rotation3D',
|
||||
full_name='carla_server.Rotation3D',
|
||||
filename=None,
|
||||
file=DESCRIPTOR,
|
||||
containing_type=None,
|
||||
fields=[
|
||||
_descriptor.FieldDescriptor(
|
||||
name='pitch', full_name='carla_server.Rotation3D.pitch', index=0,
|
||||
number=1, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='yaw', full_name='carla_server.Rotation3D.yaw', index=1,
|
||||
number=2, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='roll', full_name='carla_server.Rotation3D.roll', index=2,
|
||||
number=3, type=2, cpp_type=6, label=1,
|
||||
has_default_value=False, default_value=float(0),
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None),
|
||||
],
|
||||
extensions=[
|
||||
],
|
||||
nested_types=[],
|
||||
enum_types=[
|
||||
],
|
||||
options=None,
|
||||
is_extendable=False,
|
||||
syntax='proto3',
|
||||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=81,
|
||||
serialized_end=135,
|
||||
)
|
||||
|
||||
|
||||
_TRANSFORM = _descriptor.Descriptor(
|
||||
name='Transform',
|
||||
full_name='carla_server.Transform',
|
||||
|
@ -116,6 +161,13 @@ _TRANSFORM = _descriptor.Descriptor(
|
|||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=_descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\030\001'))),
|
||||
_descriptor.FieldDescriptor(
|
||||
name='rotation', full_name='carla_server.Transform.rotation', index=2,
|
||||
number=3, type=11, cpp_type=10, label=1,
|
||||
has_default_value=False, default_value=None,
|
||||
message_type=None, enum_type=None, containing_type=None,
|
||||
is_extension=False, extension_scope=None,
|
||||
options=None),
|
||||
],
|
||||
extensions=[
|
||||
|
@ -129,8 +181,8 @@ _TRANSFORM = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=81,
|
||||
serialized_end=179,
|
||||
serialized_start=138,
|
||||
serialized_end=284,
|
||||
)
|
||||
|
||||
|
||||
|
@ -174,8 +226,8 @@ _VEHICLE = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=181,
|
||||
serialized_end=301,
|
||||
serialized_start=286,
|
||||
serialized_end=406,
|
||||
)
|
||||
|
||||
|
||||
|
@ -219,8 +271,8 @@ _PEDESTRIAN = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=303,
|
||||
serialized_end=426,
|
||||
serialized_start=408,
|
||||
serialized_end=531,
|
||||
)
|
||||
|
||||
|
||||
|
@ -258,8 +310,8 @@ _TRAFFICLIGHT = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=429,
|
||||
serialized_end=577,
|
||||
serialized_start=534,
|
||||
serialized_end=682,
|
||||
)
|
||||
|
||||
|
||||
|
@ -296,8 +348,8 @@ _SPEEDLIMITSIGN = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=579,
|
||||
serialized_end=660,
|
||||
serialized_start=684,
|
||||
serialized_end=765,
|
||||
)
|
||||
|
||||
|
||||
|
@ -358,8 +410,8 @@ _AGENT = _descriptor.Descriptor(
|
|||
name='agent', full_name='carla_server.Agent.agent',
|
||||
index=0, containing_type=None, fields=[]),
|
||||
],
|
||||
serialized_start=663,
|
||||
serialized_end=892,
|
||||
serialized_start=768,
|
||||
serialized_end=997,
|
||||
)
|
||||
|
||||
|
||||
|
@ -389,8 +441,8 @@ _REQUESTNEWEPISODE = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=894,
|
||||
serialized_end=931,
|
||||
serialized_start=999,
|
||||
serialized_end=1036,
|
||||
)
|
||||
|
||||
|
||||
|
@ -420,8 +472,8 @@ _SCENEDESCRIPTION = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=933,
|
||||
serialized_end=1004,
|
||||
serialized_start=1038,
|
||||
serialized_end=1109,
|
||||
)
|
||||
|
||||
|
||||
|
@ -451,8 +503,8 @@ _EPISODESTART = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1006,
|
||||
serialized_end=1053,
|
||||
serialized_start=1111,
|
||||
serialized_end=1158,
|
||||
)
|
||||
|
||||
|
||||
|
@ -482,8 +534,8 @@ _EPISODEREADY = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1055,
|
||||
serialized_end=1084,
|
||||
serialized_start=1160,
|
||||
serialized_end=1189,
|
||||
)
|
||||
|
||||
|
||||
|
@ -541,8 +593,8 @@ _CONTROL = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1086,
|
||||
serialized_end=1180,
|
||||
serialized_start=1191,
|
||||
serialized_end=1285,
|
||||
)
|
||||
|
||||
|
||||
|
@ -628,8 +680,8 @@ _MEASUREMENTS_PLAYERMEASUREMENTS = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1376,
|
||||
serialized_end=1705,
|
||||
serialized_start=1481,
|
||||
serialized_end=1810,
|
||||
)
|
||||
|
||||
_MEASUREMENTS = _descriptor.Descriptor(
|
||||
|
@ -679,12 +731,13 @@ _MEASUREMENTS = _descriptor.Descriptor(
|
|||
extension_ranges=[],
|
||||
oneofs=[
|
||||
],
|
||||
serialized_start=1183,
|
||||
serialized_end=1705,
|
||||
serialized_start=1288,
|
||||
serialized_end=1810,
|
||||
)
|
||||
|
||||
_TRANSFORM.fields_by_name['location'].message_type = _VECTOR3D
|
||||
_TRANSFORM.fields_by_name['orientation'].message_type = _VECTOR3D
|
||||
_TRANSFORM.fields_by_name['rotation'].message_type = _ROTATION3D
|
||||
_VEHICLE.fields_by_name['transform'].message_type = _TRANSFORM
|
||||
_VEHICLE.fields_by_name['box_extent'].message_type = _VECTOR3D
|
||||
_PEDESTRIAN.fields_by_name['transform'].message_type = _TRANSFORM
|
||||
|
@ -717,6 +770,7 @@ _MEASUREMENTS_PLAYERMEASUREMENTS.containing_type = _MEASUREMENTS
|
|||
_MEASUREMENTS.fields_by_name['player_measurements'].message_type = _MEASUREMENTS_PLAYERMEASUREMENTS
|
||||
_MEASUREMENTS.fields_by_name['non_player_agents'].message_type = _AGENT
|
||||
DESCRIPTOR.message_types_by_name['Vector3D'] = _VECTOR3D
|
||||
DESCRIPTOR.message_types_by_name['Rotation3D'] = _ROTATION3D
|
||||
DESCRIPTOR.message_types_by_name['Transform'] = _TRANSFORM
|
||||
DESCRIPTOR.message_types_by_name['Vehicle'] = _VEHICLE
|
||||
DESCRIPTOR.message_types_by_name['Pedestrian'] = _PEDESTRIAN
|
||||
|
@ -738,6 +792,13 @@ Vector3D = _reflection.GeneratedProtocolMessageType('Vector3D', (_message.Messag
|
|||
))
|
||||
_sym_db.RegisterMessage(Vector3D)
|
||||
|
||||
Rotation3D = _reflection.GeneratedProtocolMessageType('Rotation3D', (_message.Message,), dict(
|
||||
DESCRIPTOR = _ROTATION3D,
|
||||
__module__ = 'carla_server_pb2'
|
||||
# @@protoc_insertion_point(class_scope:carla_server.Rotation3D)
|
||||
))
|
||||
_sym_db.RegisterMessage(Rotation3D)
|
||||
|
||||
Transform = _reflection.GeneratedProtocolMessageType('Transform', (_message.Message,), dict(
|
||||
DESCRIPTOR = _TRANSFORM,
|
||||
__module__ = 'carla_server_pb2'
|
||||
|
@ -833,4 +894,6 @@ _sym_db.RegisterMessage(Measurements.PlayerMeasurements)
|
|||
|
||||
DESCRIPTOR.has_options = True
|
||||
DESCRIPTOR._options = _descriptor._ParseOptions(descriptor_pb2.FileOptions(), _b('\370\001\001'))
|
||||
_TRANSFORM.fields_by_name['orientation'].has_options = True
|
||||
_TRANSFORM.fields_by_name['orientation']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\030\001'))
|
||||
# @@protoc_insertion_point(module_scope)
|
||||
|
|
|
@ -17,6 +17,7 @@ from . import util
|
|||
|
||||
try:
|
||||
from . import carla_server_pb2 as carla_protocol
|
||||
from carla_protocol import EpisodeReady
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import "carla_server_pb2.py", run the protobuf compiler to generate this file')
|
||||
|
||||
|
@ -96,7 +97,7 @@ class CarlaClient(object):
|
|||
data = self._world_client.read()
|
||||
if not data:
|
||||
raise RuntimeError('failed to read data from server')
|
||||
pb_message = carla_protocol.EpisodeReady()
|
||||
pb_message = EpisodeReady()
|
||||
pb_message.ParseFromString(data)
|
||||
if not pb_message.ready:
|
||||
raise RuntimeError('cannot start episode: server failed to start episode')
|
||||
|
@ -159,8 +160,6 @@ class CarlaClient(object):
|
|||
raise RuntimeError('failed to read data from server')
|
||||
pb_message = carla_protocol.SceneDescription()
|
||||
pb_message.ParseFromString(data)
|
||||
if len(pb_message.player_start_spots) < 1:
|
||||
raise RuntimeError("received 0 player start spots")
|
||||
self._sensor_names = settings._get_sensor_names(carla_settings)
|
||||
self._is_episode_requested = True
|
||||
return pb_message
|
||||
|
|
|
@ -89,12 +89,13 @@ class CarlaMap(object):
|
|||
return np.fliplr(self.map_image)
|
||||
|
||||
def get_map_lanes(self, height=None):
|
||||
if size is not None:
|
||||
img = Image.fromarray(self.map_image_lanes.astype(np.uint8))
|
||||
img = img.resize((size[1], size[0]), Image.ANTIALIAS)
|
||||
img.load()
|
||||
return np.fliplr(np.asarray(img, dtype="int32"))
|
||||
return np.fliplr(self.map_image_lanes)
|
||||
# if size is not None:
|
||||
# img = Image.fromarray(self.map_image_lanes.astype(np.uint8))
|
||||
# img = img.resize((size[1], size[0]), Image.ANTIALIAS)
|
||||
# img.load()
|
||||
# return np.fliplr(np.asarray(img, dtype="int32"))
|
||||
# return np.fliplr(self.map_image_lanes)
|
||||
raise NotImplementedError
|
||||
|
||||
def get_position_on_map(self, world):
|
||||
"""Get the position on the map for a certain world position."""
|
||||
|
|
|
@ -35,7 +35,17 @@ import time
|
|||
|
||||
try:
|
||||
import pygame
|
||||
from pygame.locals import *
|
||||
from pygame.locals import K_DOWN
|
||||
from pygame.locals import K_LEFT
|
||||
from pygame.locals import K_RIGHT
|
||||
from pygame.locals import K_SPACE
|
||||
from pygame.locals import K_UP
|
||||
from pygame.locals import K_a
|
||||
from pygame.locals import K_d
|
||||
from pygame.locals import K_q
|
||||
from pygame.locals import K_r
|
||||
from pygame.locals import K_s
|
||||
from pygame.locals import K_w
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import pygame, make sure pygame package is installed')
|
||||
|
||||
|
|
|
@ -0,0 +1,4 @@
|
|||
Pillow
|
||||
numpy
|
||||
protobuf
|
||||
pygame
|
|
@ -0,0 +1,141 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB), and the INTEL Visual Computing Lab.
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "Carla.h"
|
||||
#include "RoutePlanner.h"
|
||||
|
||||
#include "CarlaWheeledVehicle.h"
|
||||
#include "Util/RandomEngine.h"
|
||||
#include "WheeledVehicleAIController.h"
|
||||
|
||||
#include "Engine/CollisionProfile.h"
|
||||
|
||||
static bool IsSplineValid(const USplineComponent *SplineComponent)
|
||||
{
|
||||
return (SplineComponent != nullptr) &&
|
||||
(SplineComponent->GetNumberOfSplinePoints() > 1);
|
||||
}
|
||||
|
||||
static AWheeledVehicleAIController *GetVehicleController(AActor *Actor)
|
||||
{
|
||||
auto *Vehicle = (Actor->IsPendingKill() ? nullptr : Cast<ACarlaWheeledVehicle>(Actor));
|
||||
return (Vehicle != nullptr ?
|
||||
Cast<AWheeledVehicleAIController>(Vehicle->GetController()) :
|
||||
nullptr);
|
||||
}
|
||||
|
||||
static const USplineComponent *PickARoute(
|
||||
URandomEngine &RandomEngine,
|
||||
const TArray<USplineComponent *> &Routes,
|
||||
const TArray<float> &Probabilities)
|
||||
{
|
||||
check(Routes.Num() > 0);
|
||||
|
||||
if (Routes.Num() == 1) {
|
||||
return Routes[0];
|
||||
}
|
||||
|
||||
auto Index = RandomEngine.GetIntWithWeight(Probabilities);
|
||||
check((Index >= 0) && (Index < Routes.Num()));
|
||||
return Routes[Index];
|
||||
}
|
||||
|
||||
ARoutePlanner::ARoutePlanner(const FObjectInitializer& ObjectInitializer) :
|
||||
Super(ObjectInitializer)
|
||||
{
|
||||
RootComponent =
|
||||
ObjectInitializer.CreateDefaultSubobject<USceneComponent>(this, TEXT("SceneRootComponent"));
|
||||
RootComponent->SetMobility(EComponentMobility::Static);
|
||||
|
||||
TriggerVolume = CreateDefaultSubobject<UBoxComponent>(TEXT("TriggerVolume"));
|
||||
TriggerVolume->SetupAttachment(RootComponent);
|
||||
TriggerVolume->SetHiddenInGame(true);
|
||||
TriggerVolume->SetMobility(EComponentMobility::Static);
|
||||
TriggerVolume->SetCollisionProfileName(FName("OverlapAll"));
|
||||
TriggerVolume->bGenerateOverlapEvents = true;
|
||||
}
|
||||
|
||||
#if WITH_EDITOR
|
||||
void ARoutePlanner::PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent)
|
||||
{
|
||||
Super::PostEditChangeProperty(PropertyChangedEvent);
|
||||
const auto Size = Routes.Num();
|
||||
if (PropertyChangedEvent.Property && (Size != Probabilities.Num())) {
|
||||
Probabilities.Reset(Size);
|
||||
for (auto i = 0; i < Size; ++i) {
|
||||
Probabilities.Add(1.0f / static_cast<float>(Size));
|
||||
if (Routes[i] == nullptr) {
|
||||
Routes[i] = NewObject<USplineComponent>(this);
|
||||
Routes[i]->SetupAttachment(RootComponent);
|
||||
Routes[i]->SetHiddenInGame(true);
|
||||
Routes[i]->SetMobility(EComponentMobility::Static);
|
||||
Routes[i]->RegisterComponent();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // WITH_EDITOR
|
||||
|
||||
void ARoutePlanner::BeginPlay()
|
||||
{
|
||||
Super::BeginPlay();
|
||||
|
||||
if (Routes.Num() < 1) {
|
||||
UE_LOG(LogCarla, Warning, TEXT("ARoutePlanner has no route assigned."));
|
||||
return;
|
||||
}
|
||||
|
||||
for (auto &&Route : Routes) {
|
||||
if (!IsSplineValid(Route)) {
|
||||
UE_LOG(LogCarla, Error, TEXT("ARoutePlanner has a route with zero way-points."));
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// Register delegate on begin overlap.
|
||||
if (!TriggerVolume->OnComponentBeginOverlap.IsAlreadyBound(this, &ARoutePlanner::OnTriggerBeginOverlap))
|
||||
{
|
||||
TriggerVolume->OnComponentBeginOverlap.AddDynamic(this, &ARoutePlanner::OnTriggerBeginOverlap);
|
||||
}
|
||||
}
|
||||
|
||||
void ARoutePlanner::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||
{
|
||||
// Deregister the delegate.
|
||||
if (TriggerVolume->OnComponentBeginOverlap.IsAlreadyBound(this, &ARoutePlanner::OnTriggerBeginOverlap))
|
||||
{
|
||||
TriggerVolume->OnComponentBeginOverlap.RemoveDynamic(this, &ARoutePlanner::OnTriggerBeginOverlap);
|
||||
}
|
||||
|
||||
Super::EndPlay(EndPlayReason);
|
||||
}
|
||||
|
||||
void ARoutePlanner::OnTriggerBeginOverlap(
|
||||
UPrimitiveComponent * /*OverlappedComp*/,
|
||||
AActor *OtherActor,
|
||||
UPrimitiveComponent * /*OtherComp*/,
|
||||
int32 /*OtherBodyIndex*/,
|
||||
bool /*bFromSweep*/,
|
||||
const FHitResult & /*SweepResult*/)
|
||||
{
|
||||
auto *Controller = GetVehicleController(OtherActor);
|
||||
auto *RandomEngine = (Controller != nullptr ? Controller->GetRandomEngine() : nullptr);
|
||||
if (RandomEngine != nullptr)
|
||||
{
|
||||
auto *Route = PickARoute(*RandomEngine, Routes, Probabilities);
|
||||
|
||||
TArray<FVector> WayPoints;
|
||||
const auto Size = Route->GetNumberOfSplinePoints();
|
||||
check(Size > 1);
|
||||
WayPoints.Reserve(Size);
|
||||
for (auto i = 1; i < Size; ++i)
|
||||
{
|
||||
WayPoints.Add(Route->GetLocationAtSplinePoint(i, ESplineCoordinateSpace::World));
|
||||
}
|
||||
|
||||
Controller->SetFixedRoute(WayPoints);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,56 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB), and the INTEL Visual Computing Lab.
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "GameFramework/Actor.h"
|
||||
#include "Components/BoxComponent.h"
|
||||
#include "Components/SplineComponent.h"
|
||||
#include "RoutePlanner.generated.h"
|
||||
|
||||
/// Assign a random route to every ACarlaWheeledVehicle entering the trigger
|
||||
/// volume. Routes must be added in editor after placing this actor into the
|
||||
/// world. Spline tangents are ignored, only locations are taken into account
|
||||
/// for making the route.
|
||||
UCLASS()
|
||||
class CARLA_API ARoutePlanner : public AActor
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
public:
|
||||
|
||||
ARoutePlanner(const FObjectInitializer& ObjectInitializer);
|
||||
|
||||
protected:
|
||||
|
||||
#if WITH_EDITOR
|
||||
virtual void PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent) override;
|
||||
#endif // WITH_EDITOR
|
||||
|
||||
virtual void BeginPlay() override;
|
||||
|
||||
virtual void EndPlay(EEndPlayReason::Type EndPlayReason) override;
|
||||
|
||||
UFUNCTION()
|
||||
void OnTriggerBeginOverlap(
|
||||
UPrimitiveComponent* OverlappedComp,
|
||||
AActor *OtherActor,
|
||||
UPrimitiveComponent *OtherComp,
|
||||
int32 OtherBodyIndex,
|
||||
bool bFromSweep,
|
||||
const FHitResult &SweepResult);
|
||||
|
||||
public:
|
||||
|
||||
UPROPERTY(EditAnywhere)
|
||||
UBoxComponent *TriggerVolume;
|
||||
|
||||
UPROPERTY(BlueprintReadWrite, Category="Traffic Routes", EditAnywhere)
|
||||
TArray<USplineComponent *> Routes;
|
||||
|
||||
UPROPERTY(BlueprintReadWrite, Category="Traffic Routes", EditAnywhere, EditFixedSize)
|
||||
TArray<float> Probabilities;
|
||||
};
|
|
@ -59,6 +59,13 @@ static bool IsThereAnObstacleAhead(
|
|||
RayTrace(Vehicle, StartLeft, EndLeft);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
static void ClearQueue(std::queue<T> &Queue)
|
||||
{
|
||||
std::queue<T> EmptyQueue;
|
||||
Queue.swap(EmptyQueue);
|
||||
}
|
||||
|
||||
// =============================================================================
|
||||
// -- Constructor and destructor -----------------------------------------------
|
||||
// =============================================================================
|
||||
|
@ -118,8 +125,7 @@ void AWheeledVehicleAIController::ConfigureAutopilot(const bool Enable)
|
|||
Vehicle->SetReverse(false);
|
||||
Vehicle->SetHandbrakeInput(false);
|
||||
TrafficLightState = ETrafficLightState::Green;
|
||||
decltype(TargetLocations) EmptyQueue;
|
||||
TargetLocations.swap(EmptyQueue);
|
||||
ClearQueue(TargetLocations);
|
||||
Vehicle->SetAIVehicleState(
|
||||
bAutopilotEnabled ?
|
||||
ECarlaWheeledVehicleState::FreeDriving :
|
||||
|
@ -130,8 +136,13 @@ void AWheeledVehicleAIController::ConfigureAutopilot(const bool Enable)
|
|||
// -- Traffic ------------------------------------------------------------------
|
||||
// =============================================================================
|
||||
|
||||
void AWheeledVehicleAIController::SetFixedRoute(const TArray<FVector> &Locations)
|
||||
void AWheeledVehicleAIController::SetFixedRoute(
|
||||
const TArray<FVector> &Locations,
|
||||
const bool bOverwriteCurrent)
|
||||
{
|
||||
if (bOverwriteCurrent) {
|
||||
ClearQueue(TargetLocations);
|
||||
}
|
||||
for (auto &Location : Locations) {
|
||||
TargetLocations.emplace(Location);
|
||||
}
|
||||
|
|
|
@ -177,7 +177,7 @@ public:
|
|||
|
||||
/// Set a fixed route to follow if autopilot is enabled.
|
||||
UFUNCTION(Category = "Wheeled Vehicle Controller", BlueprintCallable)
|
||||
void SetFixedRoute(const TArray<FVector> &Locations);
|
||||
void SetFixedRoute(const TArray<FVector> &Locations, bool bOverwriteCurrent=true);
|
||||
|
||||
/// @}
|
||||
// ===========================================================================
|
||||
|
|
|
@ -56,10 +56,18 @@ static inline void Set(carla_vector3d &lhs, const FVector &rhs)
|
|||
lhs = {rhs.X, rhs.Y, rhs.Z};
|
||||
}
|
||||
|
||||
static inline void Set(carla_rotation3d &lhs, const FRotator &rhs)
|
||||
{
|
||||
lhs.pitch = rhs.Pitch;
|
||||
lhs.roll = rhs.Roll;
|
||||
lhs.yaw = rhs.Yaw;
|
||||
}
|
||||
|
||||
static inline void Set(carla_transform &lhs, const FTransform &rhs)
|
||||
{
|
||||
Set(lhs.location, rhs.GetLocation());
|
||||
Set(lhs.orientation, rhs.GetRotation().GetForwardVector());
|
||||
Set(lhs.rotation, rhs.Rotator());
|
||||
}
|
||||
|
||||
static void Set(carla_image &cImage, const FCapturedImage &uImage)
|
||||
|
|
|
@ -1,77 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB), and the INTEL Visual Computing Lab.
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "Carla.h"
|
||||
#include "IntersectionEntrance.h"
|
||||
|
||||
|
||||
// Sets default values
|
||||
AIntersectionEntrance::AIntersectionEntrance(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
|
||||
{
|
||||
// Set this actor to call Tick() every frame. You can turn this off to improve performance if you don't need it.
|
||||
PrimaryActorTick.bCanEverTick = true;
|
||||
}
|
||||
|
||||
// Called when the game starts or when spawned
|
||||
void AIntersectionEntrance::BeginPlay()
|
||||
{
|
||||
Super::BeginPlay();
|
||||
|
||||
}
|
||||
|
||||
// Called every frame
|
||||
void AIntersectionEntrance::Tick(float DeltaTime)
|
||||
{
|
||||
Super::Tick(DeltaTime);
|
||||
|
||||
}
|
||||
|
||||
TArray<FVector> AIntersectionEntrance::GetRoute(int it)
|
||||
{
|
||||
TArray<AActor*> points = Routes[it].points;
|
||||
TArray<FVector> route;
|
||||
|
||||
for (int i = 0; i < points.Num(); ++i){
|
||||
route.Add(points[i]->GetActorLocation());
|
||||
}
|
||||
|
||||
return route;
|
||||
}
|
||||
|
||||
float AIntersectionEntrance::GetProbability(int it)
|
||||
{
|
||||
return Routes[it].probability;
|
||||
}
|
||||
|
||||
/*
|
||||
#if WITH_EDITOR
|
||||
|
||||
void AIntersectionEntrance::PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent)
|
||||
{
|
||||
Super::PostEditChangeProperty(PropertyChangedEvent);
|
||||
if (PropertyChangedEvent.Property) {
|
||||
if (bCreateRoutes && (GetWorld() != nullptr)) {
|
||||
//ClearRoutes();
|
||||
for (int i = 0; i < Routes.Num(); ++i){
|
||||
for(int e = 0; e < Routes[i].points.Num(); ++e){
|
||||
AActor* actor= GetWorld()->SpawnActor<AActor>();//USphereComponent* createdComp = NewObject<USphereComponent>(this);//CreateDefaultSubobject<USphereComponent>(TEXT("Sphere"));
|
||||
USceneComponent* SphereMesh = NewObject<USceneComponent>(actor);
|
||||
SphereMesh->AttachToComponent(RootComponent,FAttachmentTransformRules::KeepWorldTransform);
|
||||
if(actor)
|
||||
{
|
||||
actor->RegisterAllComponents();
|
||||
Routes[i].points[e] = actor;
|
||||
//Routes[i].points[e].position = createdComp->GetRelativeTransform().GetLocation();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
bCreateRoutes = false;
|
||||
}
|
||||
#endif // WITH_EDITOR
|
||||
*/
|
||||
|
|
@ -1,63 +0,0 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB), and the INTEL Visual Computing Lab.
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "GameFramework/Actor.h"
|
||||
#include "IntersectionEntrance.generated.h"
|
||||
|
||||
USTRUCT(BlueprintType)
|
||||
struct FRoute {
|
||||
|
||||
GENERATED_BODY()
|
||||
|
||||
UPROPERTY(BlueprintReadWrite, Category=TrafficRoutes, EditAnywhere)
|
||||
TArray < AActor *> points;
|
||||
|
||||
UPROPERTY(BlueprintReadWrite, Category=TrafficRoutes, EditAnywhere)
|
||||
float probability = 0.0f;
|
||||
};
|
||||
|
||||
|
||||
UCLASS(BlueprintType)
|
||||
class CARLA_API AIntersectionEntrance : public AActor
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
public:
|
||||
// Sets default values for this actor's properties
|
||||
AIntersectionEntrance(const FObjectInitializer& ObjectInitializer);
|
||||
|
||||
protected:
|
||||
// Called when the game starts or when spawned
|
||||
virtual void BeginPlay() override;
|
||||
|
||||
public:
|
||||
// Called every frame
|
||||
virtual void Tick(float DeltaTime) override;
|
||||
|
||||
protected:
|
||||
|
||||
UFUNCTION(BlueprintCallable, Category="Trigger")
|
||||
TArray<FVector> GetRoute(int route);
|
||||
|
||||
UFUNCTION(BlueprintCallable, Category="Trigger")
|
||||
float GetProbability(int route);
|
||||
/*
|
||||
#if WITH_EDITOR
|
||||
virtual void PostEditChangeProperty(FPropertyChangedEvent& PropertyChangedEvent) override;
|
||||
#endif // WITH_EDITOR
|
||||
*/
|
||||
public:
|
||||
|
||||
UPROPERTY(Category = "Routes", EditAnywhere)
|
||||
bool bCreateRoutes = false;
|
||||
|
||||
|
||||
UPROPERTY(BlueprintReadWrite, Category=TrafficRoutes, EditAnywhere)
|
||||
TArray< FRoute > Routes;
|
||||
|
||||
};
|
|
@ -265,6 +265,7 @@ void UCarlaSettings::LogSettings() const
|
|||
for (auto &Item : CameraDescriptions) {
|
||||
UE_LOG(LogCarla, Log, TEXT("[%s/%s]"), S_CARLA_SCENECAPTURE, *Item.Key);
|
||||
UE_LOG(LogCarla, Log, TEXT("Image Size = %dx%d"), Item.Value.ImageSizeX, Item.Value.ImageSizeY);
|
||||
UE_LOG(LogCarla, Log, TEXT("FOV = %f"), Item.Value.FOVAngle);
|
||||
UE_LOG(LogCarla, Log, TEXT("Camera Position = (%s)"), *Item.Value.Position.ToString());
|
||||
UE_LOG(LogCarla, Log, TEXT("Camera Rotation = (%s)"), *Item.Value.Rotation.ToString());
|
||||
UE_LOG(LogCarla, Log, TEXT("Post-Processing = %s"), *PostProcessEffect::ToString(Item.Value.PostProcessEffect));
|
||||
|
|
|
@ -28,6 +28,12 @@ extern "C" {
|
|||
float z;
|
||||
};
|
||||
|
||||
struct carla_rotation3d {
|
||||
float pitch;
|
||||
float yaw;
|
||||
float roll;
|
||||
};
|
||||
|
||||
struct carla_image {
|
||||
uint32_t width;
|
||||
uint32_t height;
|
||||
|
@ -45,6 +51,7 @@ extern "C" {
|
|||
struct carla_transform {
|
||||
struct carla_vector3d location;
|
||||
struct carla_vector3d orientation;
|
||||
struct carla_rotation3d rotation;
|
||||
};
|
||||
|
||||
#define CARLA_SERVER_AGENT_UNKNOWN 0u
|
||||
|
|
|
@ -34,10 +34,18 @@ namespace server {
|
|||
lhs->set_z(rhs.z);
|
||||
}
|
||||
|
||||
static void Set(cs::Rotation3D *lhs, const carla_rotation3d &rhs) {
|
||||
DEBUG_ASSERT(lhs != nullptr);
|
||||
lhs->set_pitch(rhs.pitch);
|
||||
lhs->set_roll(rhs.roll);
|
||||
lhs->set_yaw(rhs.yaw);
|
||||
}
|
||||
|
||||
static void Set(cs::Transform *lhs, const carla_transform &rhs) {
|
||||
DEBUG_ASSERT(lhs != nullptr);
|
||||
Set(lhs->mutable_location(), rhs.location);
|
||||
Set(lhs->mutable_orientation(), rhs.orientation);
|
||||
Set(lhs->mutable_rotation(), rhs.rotation);
|
||||
}
|
||||
|
||||
static void Set(cs::Control *lhs, const carla_control &rhs) {
|
||||
|
|
|
@ -62,10 +62,10 @@ TEST(CarlaServerAPI, SimBlocking) {
|
|||
};
|
||||
|
||||
const carla_transform start_locations[] = {
|
||||
{carla_vector3d{0.0f, 0.0f, 0.0f}, carla_vector3d{0.0f, 0.0f, 0.0f}},
|
||||
{carla_vector3d{1.0f, 0.0f, 0.0f}, carla_vector3d{1.0f, 0.0f, 0.0f}},
|
||||
{carla_vector3d{0.0f, 1.0f, 0.0f}, carla_vector3d{0.0f, 1.0f, 0.0f}},
|
||||
{carla_vector3d{1.0f, 1.0f, 0.0f}, carla_vector3d{1.0f, 1.0f, 0.0f}}
|
||||
{carla_vector3d{0.0f, 0.0f, 0.0f}, carla_vector3d{0.0f, 0.0f, 0.0f}, carla_rotation3d{0.0f, 0.0f, 0.0f}},
|
||||
{carla_vector3d{1.0f, 0.0f, 0.0f}, carla_vector3d{1.0f, 0.0f, 0.0f}, carla_rotation3d{0.0f, 0.0f, 0.0f}},
|
||||
{carla_vector3d{0.0f, 1.0f, 0.0f}, carla_vector3d{0.0f, 1.0f, 0.0f}, carla_rotation3d{0.0f, 0.0f, 0.0f}},
|
||||
{carla_vector3d{1.0f, 1.0f, 0.0f}, carla_vector3d{1.0f, 1.0f, 0.0f}, carla_rotation3d{0.0f, 0.0f, 0.0f}}
|
||||
};
|
||||
|
||||
const auto S = CARLA_SERVER_SUCCESS;
|
||||
|
|
|
@ -20,12 +20,16 @@ message Vector3D {
|
|||
float z = 3;
|
||||
}
|
||||
|
||||
message Rotation3D {
|
||||
float pitch = 1;
|
||||
float yaw = 2;
|
||||
float roll = 3;
|
||||
}
|
||||
|
||||
message Transform {
|
||||
Vector3D location = 1;
|
||||
// For now, orientation as the cartesian coordinates X, Y, Z. But we are
|
||||
// probably better off using Roll, Pitch, Yaw in the future as it gives more
|
||||
// info.
|
||||
Vector3D orientation = 2;
|
||||
Vector3D orientation = 2 [deprecated=true];
|
||||
Rotation3D rotation = 3;
|
||||
}
|
||||
|
||||
message Vehicle {
|
||||
|
|
Loading…
Reference in New Issue