This commit is contained in:
2026-02-26 09:48:16 +07:00
parent e8d5980572
commit 148a5e2c60
158 changed files with 9014 additions and 1 deletions

View File

@@ -0,0 +1,64 @@
<?xml version="1.0" ?>
<launch>
<arg name="gui" default="true" />
<arg name="world_name" default="worlds/empty.world"/> <!-- Note: the world_name is with respect to GAZEBO_RESOURCE_PATH environmental variable, but can also be an absolute path -->
<arg name="robot_x" default="0.0" />
<arg name="robot_y" default="0.0" />
<arg name="robot_yaw" default="0.0" />
<arg name="robot_type" default="cititruck-01" />
<arg name="tf_prefix" default="" doc="tf_prefix to be used by gazebo plugins and in the robot's urdf etc." />
<arg name="namespace" default="$(arg tf_prefix)" doc="Namespace to push all topics into."/>
<group if="$(eval namespace != '')">
<group>
<remap from="$(arg namespace)/joint_states" to="$(arg namespace)/cititruck/joint_states" />
<remap from="$(arg namespace)/mobile_base_controller/cmd_vel" to="$(arg namespace)/cmd_vel" />
<remap from="$(arg namespace)/mobile_base_controller/odom" to="$(arg namespace)/odom" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="paused" value="true" />
<arg name="gui" value="$(arg gui)" />
</include>
</group>
<group ns="$(arg namespace)">
<!-- spawn robot and bring up controllers etc. -->
<include file="$(find cititruck_gazebo)/launch/cititruck_gazebo_common.launch">
<arg name="robot_x" value="$(arg robot_x)" />
<arg name="robot_y" value="$(arg robot_y)" />
<arg name="robot_yaw" value="$(arg robot_yaw)" />
<arg name="robot_type" value="$(arg robot_type)" />
<arg name="tf_prefix" value="$(arg tf_prefix)" />
</include>
</group>
</group>
<!-- Duplicate of the above in case namespace is empty. This is necessary to
avoid the "<group> tag has an empty 'ns' attribute" parsing error. -->
<group unless="$(eval namespace != '')">
<group>
<remap from="joint_states" to="cititruck/joint_states" />
<remap from="mobile_base_controller/cmd_vel" to="cmd_vel" />
<remap from="mobile_base_controller/odom" to="odom" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="paused" value="true" />
<arg name="gui" value="$(arg gui)" />
</include>
</group>
<!-- spawn robot and bring up controllers etc. -->
<include file="$(find cititruck_gazebo)/launch/cititruck_gazebo_common.launch">
<arg name="robot_x" value="$(arg robot_x)" />
<arg name="robot_y" value="$(arg robot_y)" />
<arg name="robot_yaw" value="$(arg robot_yaw)" />
<arg name="robot_type" value="$(arg robot_type)" />
<arg name="tf_prefix" value="$(arg tf_prefix)" />
</include>
</group>
</launch>

View File

@@ -0,0 +1,71 @@
<?xml version="1.0" ?>
<launch>
<arg name="robot_x" default="0.0" />
<arg name="robot_y" default="0.0" />
<arg name="robot_yaw" default="0.0" />
<arg name="robot_type" default="cititruck-01" />
<arg name="tf_prefix" default="" doc="tf_prefix to be used by gazebo plugins and in the robot's urdf etc." />
<arg name="prefix" value="$(arg tf_prefix)/" if="$(eval tf_prefix != '')" /> <!-- $(arg prefix) is used in all the config files! TODO: For multiple robots, create groups when loading the parameters to overwrite the arg? -->
<arg name="prefix" value="" unless="$(eval tf_prefix != '')" />
<arg name="model_name" default="cititruck" doc="Name of the Gazebo robot model (needs to be different for each robot)" />
<!-- Load URDF -->
<include file="$(find cititruck_description)/launch/upload_cititruck_urdf.launch">
<arg name="tf_prefix" value="$(arg tf_prefix)" />
<arg name="robot_type" value="$(arg robot_type)" />
</include>
<!-- Spawn the robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model $(arg model_name)
-x $(arg robot_x) -y $(arg robot_y) -Y $(arg robot_yaw) " respawn="false"/>
<!-- Load ros_control controller configurations -->
<rosparam file="$(find cititruck_description)/config/joint_state_controller.yaml" command="load" />
<rosparam file="$(find cititruck_description)/config/steerdrive_controller.yaml" command="load" subst_value="true" />
<!-- Start the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"
args="joint_state_controller mobile_base_controller"/>
<!-- EKF -->
<include file="$(find cititruck_gazebo)/launch/includes/ekf.launch.xml">
<arg name="tf_prefix" value="$(arg prefix)" />
</include>
<!-- Add passive + mimic joints to joint_states topic -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" output="screen" >
<rosparam param="source_list">[cititruck/joint_states]</rosparam>
<param name="rate" value="200.0" />
</node>
<!-- Robot state publisher -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" />
<!-- Load teleop -->
<node name="rqt_robot_steering" pkg="rqt_robot_steering" type="rqt_robot_steering">
<param name="default_topic" value="cmd_vel"/>
<param name="default_vx_max" value="1.0" />
<param name="default_vx_min" value="-1.0" />
<param name="default_vw_max" value="1.57079" />
<param name="default_vw_min" value="-1.57079" />
</node>
<!-- create combined scan topic (like on real cititruck) -->
<node pkg="topic_tools" type="relay" name="l_scan_relay" args="l_scan scan"/>
<node pkg="topic_tools" type="relay" name="r_scan_relay" args="r_scan scan"/>
<node name="l_rep117_laser_filter" pkg="cititruck_driver" type="rep117_filter.py" output="screen">
<remap from="scan" to="l_scan" />
<remap from="scan_filtered" to="l_scan_rep117" />
</node>
<node name="r_rep117_laser_filter" pkg="cititruck_driver" type="rep117_filter.py" output="screen">
<remap from="scan" to="r_scan" />
<remap from="scan_filtered" to="r_scan_rep117" />
</node>
</launch>

View File

@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<launch>
<arg name="gui" default="true" />
<arg name="robot_type" default="cititruck-01" />
<arg name="tf_prefix" default="" doc="tf_prefix to be used by gazebo plugins and in the robot's urdf etc." />
<arg name="robot_x" default="0.0" />
<arg name="robot_y" default="0.0" />
<arg name="robot_yaw" default="0.0" />
<include file="$(find cititruck_gazebo)/launch/cititruck_empty_world.launch">
<arg name="gui" value="$(arg gui)" />
<arg name="robot_type" value="$(arg robot_type)" />
<arg name="tf_prefix" value="$(arg tf_prefix)" />
<arg name="robot_x" value="$(arg robot_x)" />
<arg name="robot_y" value="$(arg robot_y)" />
<arg name="robot_yaw" value="$(arg robot_yaw)" />
</include>
<include file="$(find cititruck_gazebo)/launch/includes/spawn_maze.launch.xml" />
</launch>

View File

@@ -0,0 +1,17 @@
<?xml version="1.0" ?>
<launch>
<arg name="delta_x" default="0.0" />
<arg name="delta_y" default="0.0" />
<arg name="delta_yaw" default="0.0" />
<arg name="odom_frame_id" default="odom"/>
<arg name="base_frame_id" default="base_footprint"/>
<node name="fake_localization" pkg="fake_localization" type="fake_localization" output="screen">
<param name="odom_frame_id" value="$(arg odom_frame_id)"/>
<param name="base_frame_id" value="$(arg base_frame_id)"/>
<param name="delta_x" value="$(arg delta_x)" />
<param name="delta_y" value="$(arg delta_y)" />
<param name="delta_yaw" value="$(arg delta_yaw)" />
</node>
</launch>

View File

@@ -0,0 +1,7 @@
<?xml version="1.0"?>
<launch>
<arg name="tf_prefix" default="" />
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization_node" clear_params="true" output="screen">
<rosparam command="load" file="$(find cititruck_gazebo)/config/ekf.yaml" subst_value="true" />
</node>
</launch>

View File

@@ -0,0 +1,5 @@
<?xml version="1.0"?>
<launch>
<node name="spawn_maze" pkg="gazebo_ros" type="spawn_model" args="-sdf
-file $(find cititruck_gazebo)/sdf/maze/model.sdf -model walls" output="screen" />
</launch>