この記事は私が担当している講義ロボット知能工学特論用です。ウェイポイントナビゲーションのプログラムを作りましょう。なお、この世界モデルを使って、MCLを実装していきます。
以下のチュートリアルも参考にしてください。
ソース
// 本プログラムは // http://wiki.ros.org/ja/navigation/Tutorials/SendingSimpleGoals // を改変しています。 #include <ros/ros.h> #include <geometry_msgs/PoseWithCovarianceStamped.h> #include <move_base_msgs/MoveBaseAction.h> #include <actionlib/client/simple_action_client.h> typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient; struct MyPose { double x; double y; double yaw; }; int main(int argc, char** argv){ MyPose way_point[] = {{-0.15, -0.54, 0.0 * M_PI}, {1.6, -0.6, M_PI}, {1.6, 1.5, 0.0 * M_PI},{999, 999, 999}}; ros::Publisher pub; ros::init(argc, argv, "simple_goal"); ros::NodeHandle nh; pub= nh.advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 2, true); // 時間の取得 ros::Time tmp_time = ros::Time::now(); //create msg geometry_msgs::PoseWithCovarianceStamped initPose; // 初期位置の設定 turtlebot3_worldの初期位置が(-2.0, -0.5)なのでそれに設定 initPose.header.stamp = tmp_time; // 時間 initPose.header.frame_id = "map"; // フレーム initPose.pose.pose.position.x = -2.0; initPose.pose.pose.position.y = -0.5; initPose.pose.pose.position.z = 0; initPose.pose.pose.orientation.w = 1.0; // パブリッシュ amclパッケージに初期位置を送る pub.publish(initPose); // アクションクライアンを作成。1番目の引数は接続するアクションサーバー名。 // アクションサーバーが立ち上がっていないとだめ。 // 2番目の引数はtrueならスレッドを自動的に回す(ros::spin()。 MoveBaseClient ac("move_base", true); // アクションサーバーが起動するまで待つ。引数はタイムアウトする時間(秒)。 // この例では5秒間待つ(ブロックされる) while(!ac.waitForServer(ros::Duration(5.0))){ ROS_INFO("Waiting for the move_base action server to come up"); } ROS_INFO("The server comes up"); move_base_msgs::MoveBaseGoal goal; // base_link座標系(ロボット座標系) goal.target_pose.header.frame_id = "base_link"; // 現在時刻 goal.target_pose.header.stamp = ros::Time::now(); int i = 0; while (ros::ok()) { // ROSではロボットの進行方向がx座標、左方向がy座標、上方向がz座標 goal.target_pose.pose.position.x = way_point[i].x; goal.target_pose.pose.position.y = way_point[i].y; goal.target_pose.pose.orientation.w = 1; ROS_INFO("Sending goal: No.%d", i+1); // サーバーにgoalを送信 ac.sendGoal(goal); // 結果が返ってくるまで30.0[s] 待つ。ここでブロックされる。 bool succeeded = ac.waitForResult(ros::Duration(30.0)); // 結果を見て、成功ならSucceeded、失敗ならFailedと表示 actionlib::SimpleClientGoalState state = ac.getState(); if(succeeded) { ROS_INFO("Succeeded: No.%d (%s)",i+1, state.toString().c_str()); } else { ROS_INFO("Failed: No.%d (%s)",i+1, state.toString().c_str()); } i++; } return 0; }
- packageのディレクトリ毎、圧縮したファイル
- 展開・ビルド方法
- $ cp simple_goal.tar ~/catkin_ws/src
- $ cd ~/catkin_ws/src
- $ tar xvf simple_goal.tar
- $ cd ~/catkin_ws
- $ catkin_make
演習
- 上で展開したsimple_goalを次の要領で実行しよう。
- まず、geditで~/.bashrcを開き、最後の行に以下を追加し保存する。これにより、毎回入力する手間がはぶける。
- export TURTLEBOT3_MODEL=burger
- まず、端末を開き次のコマンドを実行。
- $ roslaunch turtlebot3_gazebo turtlebot3_world.launch
- 演習6で作成した地図を使います。ROS演習6ができていない場合はこのmap.tarファイルをダウンロードして、次のようにホームディレクトリで展開してください。
- 2個目の端末を開き次のコマンドを実行。
- roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/maps/mymap.yaml
- 3個目の端末を開きrvizを起動する。
- rosrun rviz rviz -d `rospack find turtlebot3_navigation`/rviz/turtlebot3_nav.rviz
- 4個目の端末を開き、catkin_makeして生成したsimple_goalノードを起動する。
- $ rosrun simple_goal simple_goal
- まず、geditで~/.bashrcを開き、最後の行に以下を追加し保存する。これにより、毎回入力する手間がはぶける。
ハンズオン
- もう少し規模の大きい建物内でのナビゲーションを考えましょう。以下のワールドファイルを使い、ロボットの初位置から右奥にあるポールまでウェイポイントナビゲーションをするプログラムをつくりましょう。
- 準備
$ cd
$ mkdir downloads
- fmt_world.tarダウンロードして~/downloadsの中に保存。
$ cd downloads
$ tar xvf fmt_world.tar
$ cd fmt_world
$ sudo cp turtlebot3_fmt_world.launch ~/catkin_ws/src/turtlebot3_simulations/turtlebot3_gazebo/launch
$ sudo cp fmt.world ~/catkin_ws/src/turtlebot3_simulations/turtlebot3_gazebo/worlds
$ cp -r fmt ~/.gazebo/models
$ roslaunch turtlebot3_gazebo turtlebot3_fmt_world.launch
- 下のような建物とロボットが表示されたら終わり。右奥のボールがゴール。
- A simple_goal program with subscribe the scan topic of Turtlebot3
コメント