-
Notifications
You must be signed in to change notification settings - Fork 11
/
robile_gazebo.launch
73 lines (61 loc) · 3.37 KB
/
robile_gazebo.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
<?xml version="1.0"?>
<launch>
<!-- platform_configuration options -->
<arg name="platform_config"/> <!-- (must be defined in the 'robile_description' ros package) -->
<arg name="use_kelo_tulip" default="true"/>
<arg name="hub_wheel_controller_list"/>
<arg name="platform_max_lin_vel" default="1.0"/> <!-- in m/s -->
<arg name="platform_max_ang_vel" default="1.0"/> <!-- in rad/s -->
<!-- ROBOT SPAWN POSE -->
<arg name="init_pos_x" default="0.0"/>
<arg name="init_pos_y" default="0.0"/>
<arg name="init_pos_z" default="0.0"/>
<arg name="init_yaw" default="0.0"/>
<!-- GAZEBO SETUP ARGUMENTS -->
<arg name="use_sim_time" default="true"/>
<arg name="gazebo_gui" default="true"/>
<arg name="headless" default="true"/>
<arg name="debug" default="false"/>
<arg name="paused" default="false"/>
<!-- RViz startup options -->
<arg name="start_rviz" default="true"/>
<arg name="rviz_config" default="$(find robile_gazebo)/config/rviz/robile.rviz"/>
<!-- launch gazebo with empty world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="gui" value="$(arg gazebo_gui)"/>
<arg name="headless" value="$(arg headless)"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!-- launch robot in Gazebo -->
<param if="$(arg use_kelo_tulip)" name="robot_description"
command="$(find xacro)/xacro '$(find robile_description)/gazebo/gazebo_robile.xacro' platform_config:=$(arg platform_config)"/>
<param unless="$(arg use_kelo_tulip)" name="robot_description"
command="$(find xacro)/xacro '$(find robile_description)/gazebo/gazebo_robile.xacro' platform_config:=$(arg platform_config) movable_joints:=false"/>
<node pkg="gazebo_ros" type="spawn_model" name="spawn_robot" respawn="false" output="screen" args="-param robot_description
-urdf
-x $(arg init_pos_x)
-y $(arg init_pos_y)
-z $(arg init_pos_z)
-Y $(arg init_yaw)
-model robile">
</node>
<!-- Start the robot state publisher node to publish information of fixed joints -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="30.0" />
</node>
<group if="$(arg use_kelo_tulip)">
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find robile_gazebo)/config/ros_controller/$(arg platform_config).yaml" command="load"/>
<!-- Start the Gazebo platform controller node -->
<param name="platform_max_lin_vel" type="double" value="$(arg platform_max_lin_vel)"/>
<param name="platform_max_ang_vel" type="double" value="$(arg platform_max_ang_vel)"/>
<node name="robile_gazebo_platform_controller" pkg="robile_gazebo" type="robile_gazebo_platform_controller" />
<!-- spawn controllers -->
<node name="robile_ros_controller_spawner" pkg="controller_manager" type="spawner" output="screen"
args="joint_state_controller $(arg hub_wheel_controller_list)" />
</group>
<!-- (Optional) Start RViz -->
<node pkg="rviz" type="rviz" name="robile_rviz" args="-d $(arg rviz_config)" if="$(arg start_rviz)"/>
</launch>