Play with ROS - GerryZhang0925/dev_env GitHub Wiki

Table of Contents

1 パッケージの新規開発

1.1 パッケージの作成

パッケージstd_msgsとrospyに依存するパッケージを作成する。

  >mkdir -p ~/catkin_ws/src
  >cd ~/catkin_ws/src
  >catkin_create_pkg basic std_msgs rospy

1.2 パッケージ中にトピック送信ノードの作成

basicフォルダの下に下記内容を持つファイルtopic_publisher.pyを作成する

  #!/usr/bin/env python
  import roslib; roslib.load_manifest('basic')
  import rospy
  from std_msgs.msg import Int32
  rospy.init_node('topic_publisher')
  pub = rospy.Publisher('counter', Int32)
  rate = rospy.Rate(2)
  count = 0
  while not rospy.is_shutdown():
    pub.publish(count)
    count += 1
    rate.sleep()

またbasicフォルダの下に下記内容を持つファイルmanifest.xmlを作成する

  <package format="2">
    <depend package="std_msgs" />
  </package>

1.3 パッケージのビルド

パッケージをビルドした上、パッケージとして参照できるようにする

  >cd ~/catkin_ws
  >catkin_make
  >source devel/setup.sh
  >roscd basic

1.4 パッケージ中ノードの実行

別ターミナルでコマンドroscoreを実行し、ROSを立ち上げる。パッケージbasicに参照可能なターミナルでtopic_publisher.pyを実行する。

  >rosrun basic topic_publisher.py &

実行中のトピックを確認する

  >rostopic list
  /counter
  /rosout
  /rosout_agg

counterというトピックに発行されているメッセージを確認する

  >rostopic echo counter -n 3
  data: 1786
  ---
  data: 1787
  ---
  data: 1788
  ---

counterというトピックの詳細情報を確認する

  >rostopic info counter
  Type: std_msgs/Int32
  Publishers:
  * /topic_publish (http://gzhang-ubuntu:46825/)
  Subscribers: None

1.5 パッケージへのトピック受信ノードの追加

basicフォルダの下に下記内容を持つファイルtopic_subscriber.pyを作成する

  #!/usr/bin/env python
  import roslib; roslib.load_manifest('basics')
  import rospy
  from std_msgs.msg import Int32
  def callback(msg):
    print msg.data
  rospy.init_node('topic_subscriber')
  sub = rospy.Subscriber('counter', Int32, callback)
  rospy.spin()

1.6 トピック受信ノードの実行

topic_subscriber.pyを実行する。

  rosrun basic topic_subscriber.py

すると、下記のようにcounter値がコンソールに出力される。

  10927
  10928
  10929
  10930
  10931
  ...

手動でcounterトピックに数値1000000を送信する場合には、下記のコマンドを実行する。

  rostopic pub counter std_msgs/Int32 1000000

2 メッセージタイプの定義

2.1 メッセージタイプ定義ファイルの作成

パッケージbasicにメッセージタイプComplexを追加する場合、パッケージbasicフォルダの下にmsgフォルダを作成する。

  >roscd basic
  >mkdir msg

msgフォルダに下記内容を持つファイルComplex.msgを作成する。これは、メッセージタイプComplexはrealとimaginaryという二つのフィールドを持つことを意味する。

  float32 real
  float32 imaginary

2.2 パッケージビルド設定への定義追加

パッケージをビルドする際に、当該メッセージタイプを使った通信に必要なコードを生成してもらうため、package.xmlに下記記述を追加する

  <build_depend>message_generation</build_depend>
  <exec_depend>message_generation</exec_depend>

さらにビルド時にmessage_generationをコールするため、CMakeLists.txt中関連コードが以下になるように編集する。

  find_package(catkin REQUIRED COMPONENTS
    rospy
    std_msgs
    message_generation # Add message_generation here, after the other packages
  )
  catkin_package(
    CATKIN_DEPENDS message_runtime # This will not be the only thing here
  )
  add_message_files(
    FILES
    Complex.msg
  )
  generate_messages(
    DEPENDENCIES
    std_msgs
  )

2.3 新タイプメッセージ送信ノードの作成と実行

basicフォルダの下に下記内容を持つファイルmsg_publisher.pyを作成する

  #!/usr/bin/env python
  import roslib; roslib.load_manifest('basics')
  import rospy
  from basics.msg import Complex
  from random import random
  rospy.init_node('message_publisher')
  pub = rospy.Publisher('complex', Complex)
  rate = rospy.Rate(2)
  while not rospy.is_shutdown():
    msg = Complex()
    msg.real = random()
    msg.imaginary = random()
    pub.publish(msg)
    rate.sleep()

パッケージ情報を更新する。

  >cd ~/catkin_ws
  >catkin_make
  >rosrun basic topic_msg_publisher.py&

トピックにメッセージが更新されていることを確認する。

  >rostopic echo complex
  real: 0.293846458197
  imaginary: 0.905687391758
  ---
  real: 0.292442321777
  imaginary: 0.796929121017
  ---

2.4 メッセージ定義の確認

パッケージでのメッセージ定義を確認する。

  >rosmsg package basic
  basic/Complex

メッセージタイプ名で定義を確認する。

  >rosmsg show Complex
  [basic/Complex]:
  float32 real
  float32 imaginary

3 サービスの定義

3.1 サービス定義ファイルの作成

パッケージフォルダの下に、フォルダsrvを作成し、その下に下記内容をもつファイルWordCount.srvを作成する。

  string words
  ---
  uint32 count

3.2 パッケージビルド設定への定義追加

CMakeLists.txt中関連コードが以下になるように編集する。

  find_package(catkin REQUIRED COMPONENTS
    rospy
    std_msgs
    message_generation # Add message_generation here, after the other packages
  )
  add_service_files(
    FILES
    WordCount.srv
  )
  generate_messages(
    DEPENDENCIES
    std_msgs
  )

3.3 サービス定義の確認

パッケージをリビルドした後、サービス定義を確認する。

  >cd ~/catkin_ws
  >catkin_make
  >rossrv show WordCount
  [basic/WordCount]:
  string words
  ---
  uint32 count

3.4 サーバノードの作成

basicフォルダの下に下記内容を持つファイルsrv_server.pyを作成する。

  #!/usr/bin/env python
  import roslib; roslib.load_manifest('basics')
  import rospy
  from basics.srv import WordCount,WordCountResponse
  def count_words(request):
    return WordCountResponse(len(request.words.split()))
  rospy.init_node('service_server')
  service = rospy.Service('word_count', WordCount, count_words)
  rospy.spin()

3.5 サービスの動作確認

サーバ起動前のサービス起動状況を確認する。

  >rosservice list
  /rosout/get_loggers
  /rosout/set_logger_level

サーバを起動する。

  >rosrun basic srv_server.py &

再びサービスの起動状況を確認する。

  >rosservice list
  /rosout/get_loggers
  /rosout/set_logger_level
  /service_server/get_loggers
  /service_server/set_logger_level
  /word_count
  >rosservice info word_count
  Node: /service_server
  URI: rosrpc://gzhang-ubuntu:45830
  Type: basic/WordCount
  Args: words

3.6 サービスをコールする

コンソールからサービスをコールする。

  >rosservice call word_count 'one two three'
  count: 3

3.7 サービス利用クライアントの作成

basicフォルダの下に下記内容を持つファイルsrv_client.pyを作成する。

  #!/usr/bin/env python
  import roslib; roslib.load_manifest('basic')
  import rospy
  from basics.srv import WordCount
  import sys
  rospy.init_node('service_client')
  rospy.wait_for_service('word_count')
  word_counter = rospy.ServiceProxy('word_count', WordCount)
  words = ' '.join(sys.argv[1:])
  word_count = word_counter(words)
  print words, '->', word_count.count

3.8 サービス利用クライアントの実行

コンソールからクライアントを実行して、結果を確認する。

  >rosrun basic srv_client.py these are some words
  there are some words -> 4

4 アクションの定義

4.1 アクション定義ファイルの作成

パッケージフォルダの下に、フォルダactionを作成し、その下に下記内容をもつファイルTimer.actionを作成する。

  # Three parts: the goal, the result, and the feedback.
  # Part 1: the goal, to be sent by the client
  duration time_to_wait
  ---
  # Part 2: the result, to be sent by the server upon completion
  duration time_elapsed
  uint32 updates_sent
  ---
  # Part 3: the feedback, to be sent periodically by the server during
  # execution.
  duration time_elapsed
  duration time_remaining

4.2 パッケージビルド設定への定義追加

CMakeLists.txt中関連コードが以下になるように編集する。

  find_package(catkin REQUIRED COMPONENTS
    actionlib_msgs
  )
  add_action_files(
    DIRECTORY action
    FILES Timer.action
  )
  generate_messages(
    DEPENDENCIES
    actionlib_msgs
    std_msgs
  )
  catkin_package(
    CATKIN_DEPENDS
    actionlib_msgs
  )

4.3 アクションのビルド

アクション定義をビルドする

  >cd ~/catkin_ws
  >catkin_make

アクション関連メッセージが生成されていることを確認する.

  >ls ~/catkin_ws/devel/share/basic/msg/
  TimerAction.msg
  TimerActionResult.msg
  TimerResult.msg
  TimerActionFeedback.msg
  TimerFeedback.msg
  TimerActionGoal.msg
  TimerGoal.msg

4.4 アクションサーバの実装

basicフォルダの下に下記内容を持つファイルaction_server.pyを作成する。

  import roslib; roslib.load_manifest('basics')
  import rospy
  import time
  import actionlib
  from basics.msg import TimerAction, TimerGoal, TimerResult
  def do_timer(goal):
    start_time = time.time()
    time.sleep(goal.time_to_wait.to_sec())
    result = TimerResult()
    result.time_elapsed = rospy.Duration.from_sec(time.time() - start_time)
    result.updates_sent = 0
    server.set_succeeded(result)
  rospy.init_node('timer_action_server')
  server = actionlib.SimpleActionServer('timer', TimerAction, do_timer, False)
  server.start()
  rospy.spin()

4.5 アクションサーバの動作確認

サーバ起動前のトピック状態を確認する。

  >rostopic list
  /rosout
  /rosout_agg

サーバを起動してトピック状態を再確認する。

  >rosrun basics action_server.py &
  >rostopic list
  /rosout
  /rosout_agg
  /timer/cancel
  /timer/feedback
  /timer/goal
  /timer/result
  /timer/status

/timer/goalトピックの状態を詳しく調査する。

  >rostopic info /timer/goal
  Type: basic/TimerActionGoal
  Publishers: None
  Subscribers:
   * /timer_action_server (http://gzhang-ubuntu:34307/)

TimerActionGoalメッセージを調査する。

  >rosmsg show TimerActionGoal
  [basic/TimerActionGoal]:
  std_msgs/Header header
    uint32 seq
    time stamp
    string frame_id
  actionlib_msgs/GoalID goal_id
    time stamp
    string id
  basic/TimerGoal goal
    duration time_to_wait

4.6 アクションクライアントの作成

basicフォルダの下に下記内容を持つファイルaction_client.pyを作成する。

  import roslib; roslib.load_manifest('basics')
  import rospy
  import actionlib
  from basics.msg import TimerAction, TimerGoal, TimerResult
  rospy.init_node('timer_action_client')
  client = actionlib.SimpleActionClient('timer', TimerAction)
  client.wait_for_server()
  goal = TimerGoal()
  goal.time_to_wait = rospy.Duration.from_sec(5.0)
  client.send_goal(goal)
  client.wait_for_result()
  print('Time elapsed: %f'%(client.get_result().time_elapsed.to_sec()))

クライアントを動作させてみる。

  >rosrun basic action_client.py
  Time elapsed: 5.005098

5 turtlebot gazeboを動かす

5.1 必要パッケージのインストール

以下のコマンドでインストール。

  >sudo apt-get update
  >sudo apt-get install ros-kinetic-turtlebot-gazebo
  >sudo apt-get install ros-kinetic-turtlebot ros-kinetic-turtlebot-apps ros-kinetic-turtlebot-interactions ros-kinetic-turtlebot-simulator ros-kinetic-kobuki-ftdi ros-kinetic-ar-track-alvar-msgs
  >source /opt/ros/kinetic/setup.bash

5.2 アプリケーションの起動

起動。初回のみ約10分かかる。

  >roslaunch turtlebot_gazebo turtlebot_world.launch

別端末で、ロボットを動かすノードを起動。

  >roslaunch turtlebot_bringup minimal.launch

別端末で、キーボード操作用のノードを起動。iが前進。

  >roslaunch turtlebot_teleop keyboard_teleop.launch
  (中略)
  Moving around:
     u    i    o
     j    k    l
     m    ,    .
⚠️ **GitHub.com Fallback** ⚠️