mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
git clone https://github.com/turtlebot/turtlebot
git clone https://github.com/ncnynl/turtlebot_apps.git
git clone https://github.com/ncnynl/rplidar_ros.git
git clone https://github.com/ros-perception/slam_gmapping
git clone https://github.com/ros-perception/openslam_gmapping
cd ~/catkin_ws
catkin_make
source devel/setup.bash
export TURTLEBOT_BASE=roomba
export TURTLEBOT_STACKS=circles
export TURTLEBOT_3D_SENSOR=rplidar
export TURTLEBOT_SERIAL_PORT=/dev/ttyUSB0
lsusb
Bus 001 Device 006: ID 10c4:ea60
KERNEL==”ttyUSB*”, ATTRS{idVendor}==”10c4”, ATTRS{idProduct}==”ea60”,
MODE:=”0666”, GROUP:=”dialout”, SYMLINK+=”rplidar”
sudo usermod -a -G dialout 用户名
sudo service udev reload
sudo service udev restart
roscd turtlebot_navigation
mkdir -p laser/driver
touch rplidar_laser.launch
<launch>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB1"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
node>
<node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.0 0.0 0.18 0.0 0.0 0.0 base_link laser 100"/>
launch>
说明:
增加rplidar_gmapping.launch.xml文件,设置gmapping参数
<launch>
<arg name="scan_topic" default="scan" />
<arg name="base_frame" default="base_footprint"/>
<arg name="odom_frame" default="odom"/>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen" clear_params="true" >
<param name="base_frame" value="$(arg base_frame)"/>
<param name="odom_frame" value="$(arg odom_frame)"/>
<param name="map_update_interval" value="5"/>
<param name="maxUrange" value="6.0"/>
<param name="maxRange" value="6.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="minimumScore" value="80"/>
<param name="srr" value="0.01"/>
<param name="srt" value="0.02"/>
<param name="str" value="0.01"/>
<param name="stt" value="0.02"/>
<param name="linearUpdate" value="0.05"/>
<param name="angularUpdate" value="0.0436"/>
<param name="temporalUpdate" value="-1.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="200"/>
<param name="xmin" value="-1.0"/>
<param name="ymin" value="-1.0"/>
<param name="xmax" value="1.0"/>
<param name="ymax" value="1.0"/>
<param name="delta" value="0.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>
node>
launch>
roscd turtlebot_navigation
touch launch/irobot_rplidar_gmapping_demo.launch
<launch>
<include file="$(find turtlebot_bringup)/launch/minimal.launch"/>
<include file="$(find turtlebot_navigation)/laser/driver/rplidar_laser.launch" />
<include file="$(find turtlebot_navigation)/launch/rplidar_gmapping_params.launch.xml"/>
<include file="$(find turtlebot_navigation)/launch/move_base.launch"/>
<include file="$(find turtlebot_rviz_launchers)/launch/view_navigation.launch"/>
launch>
roscd turtlebot_navigation
touch launch/move_base.launch
"move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
<param name="footprint_padding" value="0.01" />
<param name="controller_frequency" value="10.0" />
<param name="controller_patience" value="3.0" />
<param name="oscillation_timeout" value="30.0" />
<param name="oscillation_distance" value="0.5" />
file="$(find turtlebot_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
file="$(find turtlebot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
file="$(find turtlebot_navigation)/config/local_costmap_params.yaml" command="load" />
file="$(find turtlebot_navigation)/config/global_costmap_params.yaml" command="load" />
file="$(find turtlebot_navigation)/config/base_local_planner_params.yaml" command="load" />
roscd turtlebot_navigation
mkdir -p config
touch config/costmap_common_params.yaml
touch config/lobal_costmap_params.yaml
touch config/global_costmap_params.yaml
touch config/base_local_planner_params.yaml
obstacle_range: 2.5
raytrace_range: 3.0
robot_radius: 0.17
inflation_radius: 0.18
max_obstacle_height: 0.6
min_obstacle_height: 0.0
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: /base_laser_link, data_type: LaserScan, topic: /base_scan, marking: true, clearing: true}
local_costmap:
global_frame: /odom
robot_base_frame: /base_link
update_frequency: 3.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 4.0
height: 4.0
resolution: 0.05
global_costmap:
global_frame: /odom
robot_base_frame: /base_link
update_frequency: 3.0
publish_frequency: 0.0
#static_map: true
controller_frequency: 5.0
TrajectoryPlannerROS:
max_vel_x: 0.20
min_vel_x: 0.10
max_rotational_vel: 0.4
min_in_place_rotational_vel: 0.1
acc_lim_th: 0.75
acc_lim_x: 0.50
acc_lim_y: 0.50
holonomic_robot: false
yaw_goal_tolerance: 0.05
xy_goal_tolerance: 0.1
goal_distance_bias: 0.8
path_distance_bias: 0.6
sim_time: 1.2
heading_lookahead: 0.325
oscillation_reset_dist: 0.05
vx_samples: 6
vtheta_samples: 20
dwa: false
roslaunch turtlebot_navigation irobot_rplidar_gmapping_demo.launch
roslaunch turtlebot_teleop keyboard_teleop.launch
mkdir -p ~/map
rosrun map_server map_saver -f ~/map/my_map
ls ~/map
rostopic list -v
mkdir tempbagfiles
cd tempbagfiles
rosbag record -a
rosbag info
rosbag play
默认模式下,rosbag play命令在公告每条消息后会等待一小段时间(0.2秒)后才真正开始发布bag文件中的内容。等待时间可以通过-d选项来指定。你可以通过-s参数选项让rosbag play命令等待一段时间跳过bag文件初始部分后再真正开始回放。最后一个可能比较有趣的参数选项是-r选项,它允许你通过设定一个参数来改变消息发布速率。
rostopic echo -b file.bag -p /topic > data.txt
roscore
rosmake gmapping
rosparam set use_sim_time true
rosrun gmapping slam_gmapping scan:=base_scan
rosbag play –clock filename
rosrun map_server map_saver
rosrun rviz rviz