本帖最后由 liuyu-419812 于 2015-10-16 19:09 编辑
在这里我们集成到ROS操作系统最简单和最常用的硬件:按键。一个按键或一个输入设备可以命令你的机器人做下一个任务,让一个传感器检测一个打开的盒子,或让一个电机在超过关节限制时停止,这是一个重要的安全特性。在这个教程中,我们会编写一个rosserial_arduino节点,监视正常的引脚7上的按钮的状态。每一次按键的状态改变时,它会发布一个布尔消息到题“pushed”。对于如何搭建按键电路这里就不做说明了。 参考:http://wiki.ros.org/rosserial_arduino/Tutorials/Push%20Button
可以通过在Arduino examples菜单选择ros_lib->button_exampled,打开下面的代码: - /*
- * Button Example for Rosserial
- *
- /#include <ros.h>
- #include <std_msgs/Bool.h>
- ros::NodeHandle nh;
- std_msgs::Bool pushed_msg;
- ros::Publisher pub_button("pushed", &pushed_msg);
- const int button_pin = 7;
- const int led_pin = 13;
- bool last_reading;
- long last_debounce_time=0;
- long debounce_delay=50;
- bool published = true;
- void setup()
- {
- nh.initNode();
- nh.advertise(pub_button);
- //initialize an LED output pin
- //and a input pin for our push button
- pinMode(led_pin, OUTPUT);
- pinMode(button_pin, INPUT);
- //Enable the pullup resistor on the button
- digitalWrite(button_pin, HIGH);
- //The button is a normally button
- last_reading = ! digitalRead(button_pin);
- }
- void loop()
- {
- bool reading = ! digitalRead(button_pin);
- if (last_reading!= reading)
- {
- last_debounce_time = millis();
- published = false;
- }
- //if the button value has not changed during the debounce delay
- // we know it is stable
- if ( !published && (millis() - last_debounce_time) > debounce_delay) { digitalWrite(led_pin, reading);
- pushed_msg.data = reading;
- pub_button.publish(&pushed_msg);
- published = true;
- }
- last_reading = reading;
- nh.spinOnce();
- }
复制代码 下面简要分析代码,一些代码的用法在之前已经说过,不再赘述。在代码中,使用了软件去抖。首先,定义全局变量存储按键最近读的一个值,读取的时间和去抖的延时时间,是否发布按键的值。 - bool last_reading;
- long last_debounce_time=0;
- long debounce_delay=50;
- bool published = true;
复制代码 下面,在void setup()函数里,我们初始化arduino引脚为输入引脚并配置上拉电阻。我们也初始化我们的状态变量。 - //initialize an LED output pin
- //and a input pin for our push button pinMode(led_pin, OUTPUT);
- pinMode(button_pin, INPUT);
- //Enable the pullup resistor on the button
- digitalWrite(button_pin, HIGH);
- //The button is a normally button
- last_reading = ! digitalRead(button_pin);
复制代码 最后,在void loop()函数,在每一个循环,代码读取按键的值,检查按键的状态是否改变,然后检查按键的状态是否稳定,是否已经发布。 编译上传。在新的终端窗口,启动roscore: 接着,运行rosserial客户端应用程序,确保使用正确的串口: - source ~/<ws>/install/setup.bash
- rosrun rosserial_python serial_node.py /dev/ttyACM0
复制代码 其中,<ws>为安装rosserial的工作空间 通过pushed话题观察按键值 可以在终端看到,每次按键的状态改变时,都会向ROS发送信息。按下时发送False,松开时发送True。
|