forked from Autonomous-Racing-PG/ar-tu-do
-
Notifications
You must be signed in to change notification settings - Fork 5
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
created launch-file for q_learning drive on car
- Loading branch information
Showing
1 changed file
with
120 additions
and
0 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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,120 @@ | ||
<?xml version="1.0" encoding="UTF-8"?> | ||
<launch> | ||
<arg name="joystick_type" default="xbox360"/> | ||
<arg name="record" default="false"/> | ||
<arg name="videohd" default="false"/> | ||
|
||
<!-- Mode Override | ||
1 forces manual driving | ||
2 forces autonomous driving | ||
0 uses user input to enable the modes | ||
--> | ||
<arg name="mode_override" default="0"/> | ||
|
||
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find racer_description)/urdf/racer.xacro'"/> | ||
|
||
<include file="$(find car_control)/launch/car_control.launch"> | ||
<arg name="mode_override" value="$(arg mode_override)"/> | ||
</include> | ||
|
||
<include file="$(find teleoperation)/launch/remote_control.launch"> | ||
<arg name="joystick_type" value="$(arg joystick_type)"/> | ||
</include> | ||
|
||
<!-- zed camera launch file --> | ||
<!-- Include racer with 720p camera --> | ||
<group if="$(arg videohd)"> | ||
<!--<include file="./launch/zed_720.launch"/>--> | ||
</group> | ||
|
||
<!-- Include racer with VGA camera --> | ||
<group unless="$(arg videohd)"> | ||
<!--<include file="./launch/zed.launch"/>--> | ||
</group> | ||
|
||
<!--<include file="$(find emergency_stop)/launch/emergency_stop.launch"/>--> | ||
|
||
<include file="$(find vesc_driver)/launch/vesc_driver_node.launch"/> | ||
|
||
<rosparam command="load" file="$(find vesc_sim)/config/car_config.yaml"/> | ||
|
||
<include file="$(find vesc_ackermann)/launch/vesc_to_odom_node.launch"/> | ||
|
||
|
||
<!-- wallfollowing start - please enable only one --> | ||
<!-- current implementation --> | ||
<!--<include file="$(find wallfollowing5)/launch/autonomous_driving_physical.launch"/>--> | ||
|
||
<!-- former implementation of previous group --> | ||
<include file="$(find wallfollowing2)/launch/autonomous_driving_physical.launch"> | ||
<arg name="topic_drive_param" value="/input/drive_param/wf2rl"/> | ||
</include> | ||
<!-- wallfollowing end --> | ||
|
||
<include file="$(find reinforcement_learning)/launch/drive_q_learning_time_reward.launch"> | ||
</include> | ||
|
||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"/> | ||
|
||
<include file="$(find hardware)/launch/static_wheel_publisher.launch"/> | ||
|
||
<arg name="show_rviz" default="1"/> | ||
<group if="$(eval arg('show_rviz') == 1)"> | ||
<!-- rviz start - please enable only one --> | ||
<!-- default rviz config --> | ||
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find racer_world)/launch/car.rviz"/> | ||
|
||
<!-- rviz config with enabled video recording --> | ||
<!-- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find racer_world)/launch/car_record.rviz"/> --> | ||
<!-- rviz end - please enable only one --> | ||
</group> | ||
|
||
<!--<node pkg="razor_imu_9dof" type="imu_node.py" name="imu_node">--> | ||
<!-- <rosparam file="$(find hardware)/razor_imu_config.yaml" command="load"/>--> | ||
<!-- </node>--> | ||
|
||
<!--<include file="$(find imu_velocity)/launch/car_imu_velocity.launch" /> --> | ||
|
||
<include file="$(find boxing)/launch/boxing.launch"> | ||
<arg name="topic_input_cloud" value="/scan/lidar/cartesian" /> | ||
<arg name="topic_input_colored_cloud" value="/racer/camera1/depth/points" /> | ||
<arg name="topic_voxels" value="/scan/voxels" /> | ||
</include> | ||
|
||
<include file="$(find voxel_classifier)/launch/voxel_classifier.launch"> | ||
<arg name="topic_input_voxels" value="/scan/voxels" /> | ||
<arg name="topic_output_clusters" value="/scan/clusters" /> | ||
</include> | ||
|
||
<include file="$(find wall_detection)/launch/wall_detection.launch"> | ||
<arg name="topic_input_clusters" value="/scan/clusters" /> | ||
<arg name="topic_output_walls" value="/obstacles/walls" /> | ||
<arg name="topic_output_obstacles" value="/obstacles/obstacles" /> | ||
</include> | ||
|
||
<include file="$(find car_tf)/launch/car_transformer.launch" /> | ||
|
||
<node pkg="urg_node" type="urg_node" name="urg_node"> | ||
<param name="ip_address" value="192.168.1.10"/> | ||
</node> | ||
|
||
<group if="$(arg record)"> | ||
<node pkg="image_view" type="video_recorder" name="video_record_cam"> | ||
<remap from="image" to="/zed/zed/zed_node/left/image_rect_color"/> | ||
<param name="fps" value="30" /> | ||
<param name="filename" value="output-cam.avi" /> | ||
</node> | ||
</group> | ||
|
||
<!-- publishes the approximated maximal possible speed for a certain position on the track --> | ||
<!--<node pkg="simulation_tools" type="speed_info" name="speed_info" respawn="true" output="screen"/>--> | ||
|
||
<!-- needed for logging telemetry data and provide node for rviz --> | ||
<!-- arguments --> | ||
<!-- 1: log prefix (string), default: none --> | ||
<!-- 2: length for min/max arrays (int), default: 100 --> | ||
<!-- 3: smoothing value of acceleration (int), default: 5 --> | ||
<!-- 4: whether its simulation or not (string: yes|no), default: no --> | ||
<!-- 5: whether write statistics or not (string: yes|no), default: no --> | ||
<!--<node pkg="simulation_tools" type="log_stats.py" name="log_stats" output="screen" args="wallfollowing 100 10 no yes"/>--> | ||
</launch> |