add launch files

This commit is contained in:
Darby Lim 2019-01-31 11:40:05 +09:00
parent e616bb6006
commit fc608d5d8b
5 changed files with 531 additions and 15 deletions

View File

@ -43,7 +43,7 @@ find_package(turtlebot3 REQUIRED)
################################################################################
# Install
################################################################################
install(DIRECTORY models rviz worlds
install(DIRECTORY models rviz worlds launch
DESTINATION share/${PROJECT_NAME}/
)

View File

@ -0,0 +1,38 @@
# /*******************************************************************************
# * Copyright 2019 ROBOTIS CO., LTD.
# *
# * Licensed under the Apache License, Version 2.0 (the "License");
# * you may not use this file except in compliance with the License.
# * You may obtain a copy of the License at
# *
# * http://www.apache.org/licenses/LICENSE-2.0
# *
# * Unless required by applicable law or agreed to in writing, software
# * distributed under the License is distributed on an "AS IS" BASIS,
# * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# * See the License for the specific language governing permissions and
# * limitations under the License.
# *******************************************************************************/
# /* Author: Darby Lim */
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
import launch.actions
import launch_ros.actions
def generate_launch_description():
use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time', default='true')
world = os.path.join(get_package_share_directory('turtlebot3_gazebo'), 'worlds', 'empty.world')
return LaunchDescription([
launch.actions.ExecuteProcess(
cmd=['gazebo', '--verbose', world, '-s', 'libgazebo_ros_init.so'],
output='screen'),
launch.actions.ExecuteProcess(
cmd=['ros2', 'param', 'set', '/gazebo', 'use_sim_time', use_sim_time],
output='screen'),
])

View File

@ -0,0 +1,38 @@
# /*******************************************************************************
# * Copyright 2019 ROBOTIS CO., LTD.
# *
# * Licensed under the Apache License, Version 2.0 (the "License");
# * you may not use this file except in compliance with the License.
# * You may obtain a copy of the License at
# *
# * http://www.apache.org/licenses/LICENSE-2.0
# *
# * Unless required by applicable law or agreed to in writing, software
# * distributed under the License is distributed on an "AS IS" BASIS,
# * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# * See the License for the specific language governing permissions and
# * limitations under the License.
# *******************************************************************************/
# /* Author: Darby Lim */
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
import launch.actions
import launch_ros.actions
def generate_launch_description():
use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time', default='true')
world = os.path.join(get_package_share_directory('turtlebot3_gazebo'), 'worlds', 'turtlebot3.world')
return LaunchDescription([
launch.actions.ExecuteProcess(
cmd=['gazebo', '--verbose', world, '-s', 'libgazebo_ros_init.so'],
output='screen'),
launch.actions.ExecuteProcess(
cmd=['ros2', 'param', 'set', '/gazebo', 'use_sim_time', use_sim_time],
output='screen'),
])

View File

@ -0,0 +1,454 @@
<?xml version="1.0"?>
<sdf version="1.6">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<scene>
<shadows>false</shadows>
</scene>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose frame=''>0.319654 -0.235002 9.29441 0 1.5138 0.009599</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
<physics type="ode">
<real_time_update_rate>1000.0</real_time_update_rate>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<ode>
<solver>
<type>quick</type>
<iters>150</iters>
<precon_iters>0</precon_iters>
<sor>1.400000</sor>
<use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
</solver>
<constraints>
<cfm>0.00001</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>2000.000000</contact_max_correcting_vel>
<contact_surface_layer>0.01000</contact_surface_layer>
</constraints>
</ode>
</physics>
<model name="turtlebot3">
<pose>-2.0 -0.5 0.01 0.0 0.0 0.0</pose>
<link name="base_footprint"/>
<link name="base_link">
<inertial>
<pose>-0.032 0 0.070 0 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="base_collision">
<pose>-0.032 0 0.070 0 0 0</pose>
<geometry>
<box>
<size>0.140 0.140 0.140</size>
</box>
</geometry>
</collision>
<visual name="base_visual">
<pose>-0.032 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/burger_base.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="imu_link">
<sensor name="tb3_imu" type="imu">
<always_on>true</always_on>
<update_rate>200</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</z>
</linear_acceleration>
</imu>
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=imu</argument>
</ros>
</plugin>
</sensor>
</link>
<link name="base_scan">
<inertial>
<pose>-0.020 0 0.161 0 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.125</mass>
</inertial>
<collision name="lidar_sensor_collision">
<pose>-0.020 0 0.161 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.0508</radius>
<length>0.055</length>
</cylinder>
</geometry>
</collision>
<visual name="lidar_sensor_visual">
<pose>-0.032 0 0.171 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/lds.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
<sensor name="hls_lfcd_lds" type="ray">
<always_on>true</always_on>
<visualize>true</visualize>
<pose>-0.032 0 0.171 0 0 0</pose>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015000</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
</plugin>
</sensor>
</link>
<link name="wheel_left_link">
<inertial>
<pose>0 0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="wheel_left_collision">
<pose>0 0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<!-- This friction pamareter don't contain reliable data!! -->
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="wheel_left_visual">
<pose>0 0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/left_tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="wheel_right_link">
<inertial>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="wheel_right_collision">
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<!-- This friction pamareter don't contain reliable data!! -->
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="wheel_right_visual">
<pose>0.0 -0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/right_tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name='caster_back_link'>
<pose>-0.081 0 -0.004 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.00001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.00001</iyy>
<iyz>0.000</iyz>
<izz>0.00001</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.005000</radius>
</sphere>
</geometry>
<surface>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<joint name="base_joint" type="fixed">
<parent>base_footprint</parent>
<child>base_link</child>
<pose>0.0 0.0 0.010 0 0 0</pose>
</joint>
<joint name="wheel_left_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_left_link</child>
<pose>0.0 0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_right_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_right_link</child>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name='caster_back_joint' type='ball'>
<parent>base_link</parent>
<child>caster_back_link</child>
</joint>
<joint name="imu_joint" type="fixed">
<parent>base_link</parent>
<child>imu_link</child>
<pose>-0.032 0 0.068 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="lidar_joint" type="fixed">
<parent>base_link</parent>
<child>base_scan</child>
<pose>-0.032 0 0.171 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
</ros>
<update_rate>30</update_rate>
<!-- wheels -->
<left_joint>wheel_left_joint</left_joint>
<right_joint>wheel_right_joint</right_joint>
<!-- kinematics -->
<wheel_separation>0.160</wheel_separation>
<wheel_diameter>0.066</wheel_diameter>
<!-- limits -->
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>1.0</max_wheel_acceleration>
<command_topic>cmd_vel</command_topic>
<!-- output -->
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<!-- <namespace>/tb3</namespace> -->
<argument>~/out:=joint_states</argument>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
<joint_name>wheel_right_joint</joint_name>
</plugin>
</model>
</world>
</sdf>

View File

@ -1,18 +1,4 @@
<?xml version="1.0"?>
<!--
Gazebo ROS turtlebot3 demo
Run teleop node:
ros2 run turtlebot3_teleop turtlebot3_teleop_key
Try sending commands:
ros2 topic pub /tb3/cmd_vel geometry_msgs/Twist '{linear: {x: 1.0}}' -1
ros2 topic pub /tb3/cmd_vel geometry_msgs/Twist '{angular: {z: 0.1}}' -1
-->
<sdf version="1.6">
<world name="default">