-
Notifications
You must be signed in to change notification settings - Fork 662
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
fix steering and small cleanup of the interface
Signed-off-by: Maxime CLEMENT <[email protected]>
- Loading branch information
1 parent
9d16fe0
commit bf0a4b0
Showing
4 changed files
with
169 additions
and
152 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
88 changes: 52 additions & 36 deletions
88
simulator/carla_autoware/launch/carla_autoware.launch.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,40 +1,56 @@ | ||
<launch> | ||
<arg name="host" default="localhost"/> | ||
<arg name="port" default="2000"/> | ||
<arg name="timeout" default="20"/> | ||
<arg name="ego_vehicle_role_name" default="ego_vehicle"/> | ||
<arg name="vehicle_type" default="vehicle.toyota.prius"/> | ||
<arg name="spawn_point" default="None" description="location of ego vehicle spawn (default is random), example = [0.2 , 4.1, 0.4, 0., 0., 0.]"/> | ||
<arg name="carla_map" default="Town01"/> | ||
<arg name="sync_mode" default="True"/> | ||
<arg name="fixed_delta_seconds" default="0.05" description="Timestep for CARLA, FPS=1/value"/> | ||
<arg name="objects_definition_file" default="$(find-pkg-share carla_autoware)/objects.json"/> | ||
<arg name="use_traffic_manager" default="False"/> | ||
<arg name="max_real_delta_seconds" default="0.05"/> | ||
<group> | ||
<arg name="host" default="localhost"/> | ||
<arg name="port" default="2000"/> | ||
<arg name="timeout" default="20"/> | ||
<arg name="ego_vehicle_role_name" default="ego_vehicle"/> | ||
<arg name="vehicle_type" default="vehicle.toyota.prius"/> | ||
<arg name="spawn_point" default="None" description="location of ego vehicle spawn (default is random), example = [0.2 , 4.1, 0.4, 0., 0., 0.]"/> | ||
<arg name="carla_map" default="Town01"/> | ||
<arg name="sync_mode" default="True"/> | ||
<arg name="fixed_delta_seconds" default="0.05" description="Timestep for CARLA, FPS=1/value"/> | ||
<arg name="objects_definition_file" default="$(find-pkg-share carla_autoware)/objects.json"/> | ||
<arg name="use_traffic_manager" default="False"/> | ||
<arg name="max_real_delta_seconds" default="0.05"/> | ||
|
||
<!-- CARLA Interface --> | ||
<node pkg="carla_autoware" exec="carla_autoware" name="carla_autoware" output="screen"> | ||
<param name="host" value="$(var host)"/> | ||
<param name="port" value="$(var port)"/> | ||
<param name="timeout" value="$(var timeout)"/> | ||
<param name="sync_mode" value="$(var sync_mode)"/> | ||
<param name="fixed_delta_seconds" value="$(var fixed_delta_seconds)"/> | ||
<param name="carla_map" value="$(var carla_map)"/> | ||
<param name="ego_vehicle_role_name" value="$(var ego_vehicle_role_name)"/> | ||
<param name="spawn_point" value="$(var spawn_point)"/> | ||
<param name="vehicle_type" value="$(var vehicle_type)"/> | ||
<param name="objects_definition_file" value="$(var objects_definition_file)"/> | ||
<param name="use_traffic_manager" value="$(var use_traffic_manager)"/> | ||
<param name="max_real_delta_seconds" value="$(var max_real_delta_seconds)"/> | ||
</node> | ||
<!-- CARLA Interface --> | ||
<node pkg="carla_autoware" exec="carla_autoware" name="carla_autoware" output="screen"> | ||
<param name="host" value="$(var host)"/> | ||
<param name="port" value="$(var port)"/> | ||
<param name="timeout" value="$(var timeout)"/> | ||
<param name="sync_mode" value="$(var sync_mode)"/> | ||
<param name="fixed_delta_seconds" value="$(var fixed_delta_seconds)"/> | ||
<param name="carla_map" value="$(var carla_map)"/> | ||
<param name="ego_vehicle_role_name" value="$(var ego_vehicle_role_name)"/> | ||
<param name="spawn_point" value="$(var spawn_point)"/> | ||
<param name="vehicle_type" value="$(var vehicle_type)"/> | ||
<param name="objects_definition_file" value="$(var objects_definition_file)"/> | ||
<param name="use_traffic_manager" value="$(var use_traffic_manager)"/> | ||
<param name="max_real_delta_seconds" value="$(var max_real_delta_seconds)"/> | ||
</node> | ||
|
||
<!-- Awsim configuration frame to CARLA frame --> | ||
<node pkg="tf2_ros" exec="static_transform_publisher" name="velodyne_top" args="0 0 1 -1.5386 -0.015 0.001 /velodyne_top /velodyne_top_changed "/> | ||
<node pkg="tf2_ros" exec="static_transform_publisher" name="imu" args="0 0 1 -3.10519265 -0.015 -3.14059265359 /tamagawa/imu_link /tamagawa/imu_link_changed "/> | ||
<node | ||
pkg="tf2_ros" | ||
exec="static_transform_publisher" | ||
name="camera" | ||
args="-0.05 -0.0175 1.1 0.0364 -0.015 0.001 /traffic_light_left_camera/camera_link /traffic_light_left_camera/camera_link_changed " | ||
/> | ||
<arg name="input_control_cmd" default="/control/command/control_cmd"/> | ||
<arg name="input_odometry" default="/localization/kinematic_state"/> | ||
<arg name="input_steering" default="/vehicle/status/steering_status"/> | ||
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/> | ||
<arg name="config_file" default="$(find-pkg-share carla_autoware)/raw_vehicle_cmd_converter.param.yaml"/> | ||
|
||
<node pkg="raw_vehicle_cmd_converter" exec="raw_vehicle_cmd_converter_node" name="raw_vehicle_cmd_converter" output="screen"> | ||
<param from="$(var config_file)" allow_substs="true"/> | ||
<remap from="~/input/control_cmd" to="$(var input_control_cmd)"/> | ||
<remap from="~/input/odometry" to="$(var input_odometry)"/> | ||
<remap from="~/input/steering" to="$(var input_steering)"/> | ||
<remap from="~/output/actuation_cmd" to="$(var output_actuation_cmd)"/> | ||
</node> | ||
|
||
<!-- Awsim configuration frame to CARLA frame --> | ||
<node pkg="tf2_ros" exec="static_transform_publisher" name="velodyne_top" args="0 0 1 -1.5386 -0.015 0.001 /velodyne_top /velodyne_top_changed "/> | ||
<node pkg="tf2_ros" exec="static_transform_publisher" name="imu" args="0 0 1 -3.10519265 -0.015 -3.14059265359 /tamagawa/imu_link /tamagawa/imu_link_changed "/> | ||
<node | ||
pkg="tf2_ros" | ||
exec="static_transform_publisher" | ||
name="camera" | ||
args="-0.05 -0.0175 1.1 0.0364 -0.015 0.001 /traffic_light_left_camera/camera_link /traffic_light_left_camera/camera_link_changed " | ||
/> | ||
</group> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.