(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Push Button

Description: Monitor a push button and publish its state in ROS

Tutorial Level: BEGINNER

このチュートリアルはボタンを押すというROSの中に統合したいもっとも簡単でもっとも一般的なハードウェアについて書いていきます。(ロボットに次のタスクをさせるための命令や、箱が空いていることを知らせたり、関節の限界を知ってモータが動くのを止める重要なセーフティーの代わりにボタンや入力デバイスについてです。)

このチュートリアルでは、通常はoffになっている7番ピンの状態を監視するrisserial_arduinoのnodeを書きます。ボタンの状態が変わったときに"pushed"というtopicにbooleanのメッセージをパブリッシュします。

ハードウェア

このチュートリアルでは、Arduino通常はオフになっているなんらかのモメンタリースイッチか押しボタンが必要です。こののmicroswitch from Sparkfunを選ぶとよいでしょう。

ハードウェアデザインを使うのに慣れている人たちは、スイッチの入力にプルアップレジスタがないことに気づくでしょう。これはArduinoはプルアップレジスタで作られてるからです。7ピンはボタンが押されてGNDと接続するまでhighになっています。

コード

プログラムのコードは以下のようになっています。直接以下のコードをArudino IDEの新しいスケッチにコピーしてください。

   1 /* 
   2  * Button Example for Rosserial
   3  */
   4 
   5 #include <ros.h>
   6 #include <std_msgs/Bool.h>
   7 
   8 
   9 ros::NodeHandle nh;
  10 
  11 std_msgs::Bool pushed_msg;
  12 ros::Publisher pub_button("pushed", &pushed_msg);
  13 
  14 const int button_pin = 7;
  15 const int led_pin = 13;
  16 
  17 bool last_reading;
  18 long last_debounce_time=0;
  19 long debounce_delay=50;
  20 bool published = true;
  21 
  22 void setup()
  23 {
  24   nh.initNode();
  25   nh.advertise(pub_button);
  26   
  27   //initialize an LED output pin 
  28   //and a input pin for our push button
  29   pinMode(led_pin, OUTPUT);
  30   pinMode(button_pin, INPUT);
  31   
  32   //Enable the pullup resistor on the button
  33   digitalWrite(button_pin, HIGH);
  34   
  35   //The button is a normally button
  36   last_reading = ! digitalRead(button_pin);
  37  
  38 }
  39 
  40 void loop()
  41 {
  42   
  43   bool reading = ! digitalRead(button_pin);
  44   
  45   if (last_reading!= reading){
  46       last_debounce_time = millis();
  47       published = false;
  48   }
  49   
  50   //if the button value has not changed during the debounce delay
  51   // we know it is stable
  52   if ( !published && (millis() - last_debounce_time)  > debounce_delay) {
  53     digitalWrite(led_pin, reading);
  54     pushed_msg.data = reading;
  55     pub_button.publish(&pushed_msg);
  56     published = true;
  57   }
  58 
  59   last_reading = reading;
  60   
  61   nh.spinOnce();
  62 }

このコードはrosserial_arduinoが使われる典型的な例です。rosserialオブジェクトはグローバルで宣言されてます。

   9 ros::NodeHandle nh;
  10 
  11 std_msgs::Bool pushed_msg;
  12 ros::Publisher pub_button("pushed", &pushed_msg);

setup関数の中で初期化をします。

  24   nh.initNode();
  25   nh.advertise(pub_button);

そしたらloop関数の中でボタンの状態が変わったときにパブリッシュが働きます。

  55     pub_button.publish(&pushed_msg);

ボタンの状態を監視する

このセンサーはボタンの状態についてのメッセージを常に垂れ流し続けるべきではありませんが、ボタンが押されたり離されるときのみパブリッシュされるべきです。この変化を見るには、ボタンの最新の状態を知り、どのぐらいこの状態が有効なのかを知る必要があります。そこで、一度状態が変化したら、センサーはボタンをデバウンスするべきです。十分長い間待っているので、ボタンの値が落ち着き振動してないことがわかります。これは、入力ピンでの電圧が、接触と切断の間にメカ的な接触が上下することになるように、(以下の図で示すように)跳ね回るからです。

コードの中で、このデバウンスは起こるところはごくわずかです。まず、ボタンの最新の状態を持っている変数と、読み取りにかかる時間、デバウンスのための遅延時間、パブリッシュされたかを持っとくグローバル変数があります。

  17 bool last_reading;
  18 long last_debounce_time=0;
  19 long debounce_delay=50;
  20 bool published = true;

つぎにsetup関数のなかで、IOとプルアップレジスタのためのArduinoのピンを初期化しました。状態変数も初期化します。

  27   //initialize an LED output pin 
  28   //and a input pin for our push button
  29   pinMode(led_pin, OUTPUT);
  30   pinMode(button_pin, INPUT);
  31   
  32   //Enable the pullup resistor on the button
  33   digitalWrite(button_pin, HIGH);
  34   
  35   //The button is a normally button
  36   last_reading = ! digitalRead(button_pin);

最後に、loop関数の中で、コードはどのループのときもボタンの状態を読み、上体が変わってないかを調べ、状態が落ち着いているかパブリッシュされているかを確認します。

テスト

roscoreを立ち上げます。

roscore

新しいターミナルで、rosserial_pythonのserial_node.pyを実行します。正しいシリアルポートを使っていることを確かめます。

rosrun rosserial_python serial_node.py /dev/ttyUSB0

さて、pushedというtopicのボタンの値を見てみましょう。

rostopic echo pushed

Wiki: ja/rosserial_arduino/jaTutorials/Push Button (last edited 2012-12-24 11:28:03 by Yuto Inagaki)