XTDrone/sitl_config/ugv/catvehicle/launch/fs-test1.launch

110 lines
5.0 KiB
XML

<?xml version="1.0" encoding="UTF-8"?>
<!--
Author: Rahul Kumar Bhadani
Copyright (c) 2020 Arizona Board of Regents
All rights reserved.
Permission is hereby granted, without written agreement and without
license or royalty fees, to use, copy, modify, and distribute this
software and its documentation for any purpose, provided that the
above copyright notice and the following two paragraphs appear in
all copies of this software.
IN NO EVENT SHALL THE ARIZONA BOARD OF REGENTS BE LIABLE TO ANY PARTY
FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
IF THE UNIVERSITY OF CALIFORNIA HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGE.
THE ARIZONA BOARD OF REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY
AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER
IS ON AN "AS IS" BASIS, AND THE UNIVERSITY OF CALIFORNIA HAS NO OBLIGATION
TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
-->
<launch>
<include file="$(find catvehicle)/launch/catvehicle_empty.launch">
</include>
<param name="enable_statistics" value="true" />
<arg name="robot" default="catvehicle"/>
<arg name="leader" default="toyota"/>
<arg name="dx_min" default = "4.5"/>
<arg name="dx_activate" default = "6.0"/>
<arg name="velodyne_points" default="false"/>
<arg name="camera_left" default="false"/>
<arg name="camera_right" default="false"/>
<arg name="triclops" default="false"/>
<arg name="ego_laser_sensor" default="true"/>
<arg name="leader_laser_sensor" default="true"/>
<arg name="obstaclestopper" default="false"/>
<arg name="rosbag" default="false"/>
<arg name="csvfile" default="/home/ivory/CyverseData/JmscslgroupData/PandaData/2020_02_18/2020-02-18-13-00-42-209119__CAN_Messages.csv"/>
<arg name="dbcfile" default="/home/ivory/VersionControl/Jmscslgroup/strym/examples/newToyotacode.dbc"/>
<group ns="$(arg leader)">
<param name="robot_description"
command="$(find xacro)/xacro.py '$(find catvehicle)/urdf/catvehicle.xacro' roboname:='$(arg leader)' camera_left:='$(arg camera_left)' camera_right:='$(arg camera_right)' triclops:='$(arg triclops)' velodyne_points:='$(arg velodyne_points)' laser_points:='$(arg leader_laser_sensor)'" />
<include file="$(find catvehicle)/launch/catvehicle.launch">
<arg name="robot_name" value="$(arg leader)"/>
<arg name="obstaclestopper" value="$(arg obstaclestopper)"/>
<arg name="init_pose" value="-x 15.0 -y 0.0 -z 0.0"/>
<arg name="config_file" value="catvehicle_control.yaml"/>
</include>
<node pkg="catvehicle" type="drive_lead.py" name="drive_lead_$(arg leader)" output="screen" required="true" args="$(arg csvfile) $(arg dbcfile)">
<remap from="cmd_vel" to="cmd_control_vel"/>
</node>
<node pkg="hoffmansubsystem" type="hoffmansubsystem_node" name="hoffmansubsystem_$(arg leader)" output="screen" required="true"/>
</group>
<node name="recorder" pkg="rosbag" type="record" output="screen" args=" -o /home/ivory/VersionControl/Jmscslgroup/safetyfs/bagfiles/fs-test1_dxmin_$(arg dx_min)_dx_activate_$(arg dx_activate) -a" if="$(arg rosbag)"/>
<group ns="$(arg robot)">
<param name="robot_description"
command="$(find xacro)/xacro.py '$(find catvehicle)/urdf/catvehicle.xacro' roboname:='$(arg robot)' camera_left:='$(arg camera_left)' camera_right:='$(arg camera_right)' triclops:='$(arg triclops)' velodyne_points:='$(arg velodyne_points)' laser_points:='$(arg ego_laser_sensor)'" />
<include file="$(find catvehicle)/launch/catvehicle.launch">
<arg name="robot_name" value="$(arg robot)"/>
<arg name="obstaclestopper" value="$(arg obstaclestopper)"/>
<arg name="init_pose" value="-x 0.0 -y 0.0 -z 0.0"/>
<arg name="config_file" value="catvehicle_control.yaml"/>
</include>
<!--node pkg="kf" type="kf_node" name="kf_$(arg robot)" output="screen" required="true">
<remap from="d_relative" to="/$(arg robot)/distanceEstimatorSteeringBased/dist"/>
</node-->
<!--node name="velocityEstimator" pkg="catvehicle" type="velocityEstimator" output="screen">
<param name="dist_topic" value="/$(arg robot)/distanceEstimatorSteeringBased/dist"/>
<param name="vel_topic" value="/$(arg robot)/v_relative"/>
</node-->
<node pkg="fs" type="fs_node" name="fs_$(arg robot)" output="screen" required="true">
<!--remap from="v_ref" to="/$(arg leader)/vel"/-->
<remap from="d_relative" to="/$(arg robot)/distanceEstimator/dist"/>
<remap from="cmd_vel" to="cmd_control_vel"/>
</node>
<node pkg="hoffmansubsystem" type="hoffmansubsystem_node" name="hoffmansubsystem_$(arg robot)" output="screen" required="true"/>
</group>
</launch>