====== 6. 経路追従 ======
# 2015-06-08 AND
追記:パラメータファイルを変更した場合は、roscoreを含めて全てのプログラムを停止してやり直すこと。
===== パラメータファイルの作成 =====
~/catkin_ws/src/ros_study_2dnavに以下の4つのファイルを作る。
$ cd ~/catkin_ws/src
$ catkin_create_pkg ros_study_2dnav //既に作っていてある人はやらなくて良い
$ gedit costmap_common_params.yaml global_costmap_params.yaml local_costmap_params.yaml base_local_planner_params.yaml
==== costmap_common_params.yaml ====
obstacle_range: 5.0
raytrace_range: 7.0
#footprint: [[x0, y0], [x1, y1], [x2, y2], [x3, y3]]
footprint: [[0.17, 0.17], [-0.17, 0.17], [-0.17, -0.17], [0.17, -0.17]]
#robot_radius: ir_of_robot
inflation_radius: 0.3
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
コピペしたときに無駄なスペース文字が入ることがあるので、削除して下さい
footprintに、ロボット覆う多角形の頂点を記述する。この多角形は障害物回避等に用いられる。各自設定すること。
{{:ros:study:fig6-1.png|}}
==== global_costmap_params.yaml ====
global_costmap:
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0
static_map: true
コピペしたときに無駄なスペース文字が入ることがあるので、削除して下さい
==== local_costmap_params.yaml ====
local_costmap:
global_frame: odom
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 10.0
height: 10.0
resolution: 0.05
コピペしたときに無駄なスペース文字が入ることがあるので、削除して下さい
==== base_local_planner_params.yaml ====
TrajectoryPlannerROS:
max_vel_x: 0.45
min_vel_x: 0.1
max_rotational_vel: 1.0
min_in_place_rotational_vel: 0.4
acc_lim_th: 3.2
acc_lim_x: 2.5
acc_lim_y: 2.5
holonomic_robot: false
コピペしたときに無駄なスペース文字が入ることがあるので、削除して下さい
===== 起動ランチファイルの作成 =====
~/catkin_ws/src/ros_study_2dnavに以下のファイルを作る
$ gedit navigation.launch
==== navigation.launch ====
===== 実行 =====
ターミナル1
$ roscore
ターミナル2(ロボットとPCを接続しておくこと)
$ ypspur-coordinator -p your_robot.param -d /dev/ttyACM0
ターミナル3
$ rosrun ypspur_ros_bridge ypspur_ros_bridge
ターミナル4
$ rosrun hokuyo_node hokuyo_node _port:=/dev/ttyACM1 または、 $ rosrun hokuyo_node hokuyo_node _port:=/dev/ttyACM1 _min_ang:=-2.08621382713 _max_ang:=2.08621382713
ターミナル5
$ rosrun sensor_tf_test sensor_tf_test
ターミナル6
$ cd ~/ros_study
$ rosrun map_server map_server map_name.yaml
ターミナル7
$ rosrun amcl amcl または、 $ roslaunch ros_study_2dnav amcl_diff.launch
ターミナル8
$ roslaunch ros_study_2dnav navigation.launch
===== rvizによるゴールの設定 =====
ターミナル9
$ rosrun rviz rviz
下記の画像を参考に、"/move_base"のトピックを追加して見ると良い。"/move_base"のトピックは沢山あるので、色々試してみること。
{{:ros:study:fig6-2.png|}}
初期画面。ロボットの位置と姿勢が地図とずれている。
{{:ros:study:fig6-3.png|}}
下記の画像を参考に、地図と合うように現在のロボットの位置と姿勢を提示する。
{{:ros:study:fig6-4.png|}}
現在のロボットの位置と姿勢に合わせて更新される。
まだ地図と大きくずれていれば、もう一度現在の位置と姿勢を提示する。
{{:ros:study:fig6-5.png|}}
下記の画像を参考に、目標と成るロボットの位置と姿勢を提示する。
設定するとロボットが目標地点に走り始めるので注意すること
{{:ros:study:fig6-6.png|}}
rvizを閉じる前に、設定を保存しておくこと