Skip to content

Commit

Permalink
renamed carla_spawn_actors to carla_spawn_objects
Browse files Browse the repository at this point in the history
  • Loading branch information
jbmag committed Dec 9, 2020
1 parent 8b19a3f commit 4e4b71b
Show file tree
Hide file tree
Showing 20 changed files with 59 additions and 59 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ Beside the bridging functionality, there are many more features provided in sepa

| Name | Description |
| --------------------------------- | ------------------------------------------------------------------------------------------------------- |
| [Carla Spawn Actors](carla_spawn_actors/README.md) | Provides a generic way to spawn actors |
| [Carla Spawn Actors](carla_spawn_objects/README.md) | Provides a generic way to spawn actors |
| [Carla Manual Control](carla_manual_control/README.md) | A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) |
| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API |
| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. |
Expand Down
4 changes: 2 additions & 2 deletions carla_ad_demo/launch/carla_ad_demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
</include>

<!-- the ego vehicle, that will be controlled by the carla_ad_agent -->
<include file="$(find carla_spawn_actors)/launch/carla_example_ego_vehicle.launch">
<arg name="actors_definition_file" value='$(find carla_spawn_actors)/config/actors.json'/>
<include file="$(find carla_spawn_objects)/launch/carla_example_ego_vehicle.launch">
<arg name="objects_definition_file" value='$(find carla_spawn_objects)/config/objects.json'/>
<arg name='role_name' value='$(arg role_name)'/>
<arg name="spawn_point_ego_vehicle" value="$(arg spawn_point)"/>
<arg name="spawn_sensors_only" value="false"/>
Expand Down
4 changes: 2 additions & 2 deletions carla_ad_demo/launch/carla_ad_demo_with_scenario.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
</include>

<!-- the ego vehicle, that will be controlled by the carla_ad_agent -->
<include file="$(find carla_spawn_actors)/launch/carla_example_ego_vehicle.launch">
<arg name="actors_definition_file" value='$(find carla_spawn_actors)/config/actors.json'/>
<include file="$(find carla_spawn_objects)/launch/carla_example_ego_vehicle.launch">
<arg name="objects_definition_file" value='$(find carla_spawn_objects)/config/objects.json'/>
<arg name='role_name' value='$(arg role_name)'/>
<arg name="spawn_sensors_only" value="false"/>
</include>
Expand Down
2 changes: 1 addition & 1 deletion carla_ad_demo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<exec_depend>carla_ros_bridge</exec_depend>
<exec_depend>carla_spawn_actors</exec_depend>
<exec_depend>carla_spawn_objects</exec_depend>
<exec_depend>carla_waypoint_publisher</exec_depend>
<exec_depend>carla_ad_agent</exec_depend>
<exec_depend>carla_manual_control</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
</include>

<!-- the ego vehicle, that will be controlled by an agent (e.g. carla_ad_agent) -->
<include file="$(find carla_spawn_actors)/launch/carla_example_ego_vehicle.launch">
<arg name="actors_definition_file" value='$(find carla_spawn_actors)/config/actors.json'/>
<include file="$(find carla_spawn_objects)/launch/carla_example_ego_vehicle.launch">
<arg name="objects_definition_file" value='$(find carla_spawn_objects)/config/objects.json'/>
<arg name='role_name' value='$(arg role_name)'/>
<arg name="spawn_point_ego_vehicle" value="$(arg spawn_point)"/>
<arg name="spawn_sensors_only" value="false"/>
Expand Down
2 changes: 1 addition & 1 deletion carla_ros_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
<exec_depend>rosgraph_msgs</exec_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>carla_msgs</exec_depend>
<exec_depend>carla_spawn_actors</exec_depend>
<exec_depend>carla_spawn_objects</exec_depend>
<exec_depend>carla_manual_control</exec_depend>
<export>
</export>
Expand Down
6 changes: 3 additions & 3 deletions carla_ros_bridge/test/ros_bridge_client.test
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@
<arg name='enable_rosbag' default='False'/>
<rosparam file="$(find carla_ros_bridge)/config/settings.yaml" command="load" />
<param name='enable_rosbag' type="boolean" value="False"/>
<arg name="actors_definition_file" default="$(find carla_ros_bridge)/test/test_actors.json"/>
<arg name="objects_definition_file" default="$(find carla_ros_bridge)/test/test_objects.json"/>
<arg name="vehicle_filter" default='vehicle.tesla.model3'/>

<include file="$(find carla_ros_bridge)/launch/carla_ros_bridge.launch">
<arg name='host' value='$(arg host)'/>
<arg name='port' value='$(arg port)'/>
</include>

<include file="$(find carla_spawn_actors)/launch/carla_spawn_actors.launch">
<arg name="actors_definition_file" value='$(arg actors_definition_file)'/>
<include file="$(find carla_spawn_objects)/launch/carla_spawn_objects.launch">
<arg name="objects_definition_file" value='$(arg objects_definition_file)'/>
</include>

<test test-name="testPublishedData" pkg="carla_ros_bridge" type="ros_bridge_client.py" time-limit="20.0"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
{
"actors":
"objects":
[
{
"type": "sensor.pseudo.traffic_lights",
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_spawn_actors)
project(carla_spawn_objects)

find_package(catkin REQUIRED COMPONENTS rospy roslaunch)

Expand All @@ -11,9 +11,9 @@ endif()

catkin_package(CATKIN_DEPENDS rospy)

catkin_install_python(PROGRAMS src/carla_spawn_actors/carla_spawn_actors.py
catkin_install_python(PROGRAMS src/carla_spawn_objects/carla_spawn_objects.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
catkin_install_python(PROGRAMS src/carla_spawn_actors/set_initial_pose.py
catkin_install_python(PROGRAMS src/carla_spawn_objects/set_initial_pose.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

install(DIRECTORY launch/
Expand Down
10 changes: 5 additions & 5 deletions carla_spawn_actors/README.md → carla_spawn_objects/README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# ROS Carla Spawn Actors
# ROS Carla Spawn Objects

`carla_spawn_actors` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors.
`carla_spawn_objects` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors.

Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required.

Expand All @@ -22,11 +22,11 @@ Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and

## Attach sensor to an existing vehicle

It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_actors` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor.
It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_objects` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor.

## Create your own sensor setup

Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_actors` reads it from the file location defined via the private ros parameter `actors_definition_file`.
Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_objects` reads it from the file location defined via the private ros parameter `objects_definition_file`.

The format is defined like that:

Expand All @@ -52,4 +52,4 @@ The format is defined like that:

Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md).

An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [actors.json](config/actors.json)
An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [objects.json](config/objects.json)
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
{
"actors":
"objects":
[
{
"type": "sensor.pseudo.traffic_lights",
Expand Down
Original file line number Diff line number Diff line change
@@ -1,24 +1,24 @@
<!-- -->
<launch>
<arg name="role_name" default="ego_vehicle"/>
<arg name="actors_definition_file" default='$(find carla_spawn_actors)/config/actors.json'/>
<arg name="objects_definition_file" default='$(find carla_spawn_objects)/config/objects.json'/>
<!-- use comma separated format "x,y,z,roll,pitch,yaw",
and parameter name spawn_point_<vehicle_name>. You can add
as many spawn_point as vehicles defined in actors_definition_file-->
as many spawn_point as vehicles defined in objects_definition_file-->
<!-- <arg name="spawn_point_ego_vehicle" default='390.0,-87.0,0.3,0.0,0.0,90.0'/> -->
<arg name="spawn_point_ego_vehicle" default=''/>
<arg name="spawn_sensors_only" default="false"/>

<arg name="control_id" default="control"/>

<include file="$(find carla_spawn_actors)/launch/carla_spawn_actors.launch">
<arg name="actors_definition_file" value='$(arg actors_definition_file)'/>
<include file="$(find carla_spawn_objects)/launch/carla_spawn_objects.launch">
<arg name="objects_definition_file" value='$(arg objects_definition_file)'/>
<arg name="spawn_point_ego_vehicle" value="$(arg spawn_point_ego_vehicle)"/>
<arg name="spawn_sensors_only" value="$(arg spawn_sensors_only)" />
</include>

<!-- This nodes allows to respawn the vehicle <role_name> by publishing on topic /initialpose -->
<include file="$(find carla_spawn_actors)/launch/set_initial_pose.launch">
<include file="$(find carla_spawn_objects)/launch/set_initial_pose.launch">
<arg name="role_name" value="$(arg role_name)"/>
<arg name="control_id" value="$(arg control_id)"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
<!-- -->
<launch>
<arg name="actors_definition_file" default='$(find carla_spawn_actors)/config/actors.json'/>
<arg name="objects_definition_file" default='$(find carla_spawn_objects)/config/objects.json'/>
<!-- use comma separated format "x,y,z,roll,pitch,yaw",
and parameter name spawn_point_<vehicle_name>. You can add
as many spawn_point as vehicles defined in actors_definition_file-->
as many spawn_point as vehicles defined in objects_definition_file-->
<arg name="spawn_point_ego_vehicle" default=""/>
<arg name="spawn_sensors_only" default="false"/>

<node pkg="carla_spawn_actors" type="carla_spawn_actors.py" name="$(anon carla_spawn_actors)" output="screen">
<param name="actors_definition_file" value="$(arg actors_definition_file)" />
<node pkg="carla_spawn_objects" type="carla_spawn_objects.py" name="$(anon carla_spawn_objects)" output="screen">
<param name="objects_definition_file" value="$(arg objects_definition_file)" />
<param name="spawn_point_ego_vehicle" value="$(arg spawn_point_ego_vehicle)" />
<param name="spawn_sensors_only" value="$(arg spawn_sensors_only)" />
</node>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<!-- id of the actor.pseudo.control actor-->
<arg name='control_id' default='control'/>

<node pkg="carla_spawn_actors" type="set_initial_pose.py" name="set_initial_pose_$(arg role_name)" output="screen">
<node pkg="carla_spawn_objects" type="set_initial_pose.py" name="set_initial_pose_$(arg role_name)" output="screen">
<param name="role_name" value="$(arg role_name)" />
<param name="control_id" value="$(arg control_id)" />
</node>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<?xml version="1.0"?>
<package format="2">
<name>carla_spawn_actors</name>
<name>carla_spawn_objects</name>
<version>0.0.0</version>
<description>The carla_spawn_actors package</description>
<description>The carla_spawn_objects package</description>
<maintainer email="[email protected]">CARLA Simulator Team</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
Expand Down
4 changes: 2 additions & 2 deletions carla_spawn_actors/setup.py → carla_spawn_objects/setup.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
"""
Setup for carla_spawn_actors
Setup for carla_spawn_objects
"""

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['carla_spawn_actors'],
packages=['carla_spawn_objects'],
package_dir={'': 'src'}
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
base class for spawning actors in ROS
base class for spawning objects (carla actors and pseudo_actors) in ROS
Gets config file from ros parameter ~actors_definition_file and spawns corresponding actors
Gets config file from ros parameter ~objects_definition_file and spawns corresponding objects
through ROS service /carla/spawn_object.
Looks for an initial spawn point first in the launchfile, then in the config file, and
Expand All @@ -31,11 +31,11 @@
from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest

# ==============================================================================
# -- CarlaSpawnActors ------------------------------------------------------------
# -- CarlaSpawnObjects ------------------------------------------------------------
# ==============================================================================


class CarlaSpawnActors(object):
class CarlaSpawnObjects(object):

"""
Handles the spawning of the ego vehicle and its sensors
Expand All @@ -44,8 +44,8 @@ class CarlaSpawnActors(object):
"""

def __init__(self):
rospy.init_node('spawn_actors_node', anonymous=True)
self.actors_definition_file = rospy.get_param('~actors_definition_file')
rospy.init_node('spawn_objects_node', anonymous=True)
self.objects_definition_file = rospy.get_param('~objects_definition_file')
self.spawn_sensors_only = rospy.get_param('~spawn_sensors_only', None)

self.players = []
Expand All @@ -56,27 +56,27 @@ def __init__(self):
self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject)
self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject)

def spawn_actors(self):
def spawn_objects(self):
"""
Spawns the actors
Spawns the objects
Either at a given actor_spawnpoint or at a random Carla spawnpoint
Either at a given spawnpoint or at a random Carla spawnpoint
:return:
"""
# Read sensors from file
if not os.path.exists(self.actors_definition_file):
if not os.path.exists(self.objects_definition_file):
raise RuntimeError(
"Could not read sensor-definition from {}".format(self.actors_definition_file))
"Could not read sensor-definition from {}".format(self.objects_definition_file))
json_sensors = None
with open(self.actors_definition_file) as handle:
with open(self.objects_definition_file) as handle:
json_actors = json.loads(handle.read())

global_sensors = []
vehicles = []
found_sensor_actor_list = False

for actor in json_actors["actors"]:
for actor in json_actors["objects"]:
actor_type = actor["type"].split('.')[0]
if actor["type"] == "sensor.pseudo.actor_list" and self.spawn_sensors_only:
global_sensors.append(actor)
Expand All @@ -87,7 +87,7 @@ def spawn_actors(self):
vehicles.append(actor)
else:
rospy.logwarn(
"Actor with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"]))
"Object with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"]))
if self.spawn_sensors_only is True and found_sensor_actor_list is False:
raise Exception("Parameter 'spawn_sensors_only' enabled, " +
"but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.")
Expand Down Expand Up @@ -194,7 +194,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0):
(or not if global sensor)
:param sensors: list of sensors
:param attached_vehicle_id: id of vehicle to attach the sensors to
:return actors: list of ids of actors created
:return actors: list of ids of objects created
"""
actors = []
sensor_names = []
Expand Down Expand Up @@ -335,9 +335,9 @@ def run(self):
rospy.logerr("Timeout while waiting for world info!")
sys.exit(1)

rospy.loginfo("World info is available. Spawning acotrs...")
rospy.loginfo("World info is available. Spawning objects...")
rospy.on_shutdown(self.destroy)
self.spawn_actors()
self.spawn_objects()
try:
rospy.spin()
except rospy.ROSInterruptException:
Expand All @@ -352,16 +352,16 @@ def main():
"""
main function
"""
spawn_actors_node = None
spawn_objects_node = None
try:
spawn_actors_node = CarlaSpawnActors()
spawn_actors_node.run()
spawn_objects_node = CarlaSpawnObjects()
spawn_objects_node.run()
except Exception as e:
rospy.logfatal(
"Exception caught: {}".format(e))
finally:
if spawn_actors_node is not None:
spawn_actors_node.destroy()
if spawn_objects_node is not None:
spawn_objects_node.destroy()


if __name__ == '__main__':
Expand Down
2 changes: 1 addition & 1 deletion docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ ENV PYTHONPATH=/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py$PYTHON_VE

COPY carla_ackermann_control /opt/carla-ros-bridge/src/carla_ackermann_control
COPY carla_common /opt/carla-ros-bridge/src/carla_common
COPY carla_spawn_actors /opt/carla-ros-bridge/src/carla_spawn_actors
COPY carla_spawn_objects /opt/carla-ros-bridge/src/carla_spawn_objects
COPY carla_manual_control /opt/carla-ros-bridge/src/carla_manual_control
COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs
COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge
Expand Down

0 comments on commit 4e4b71b

Please sign in to comment.