本教程描述了您可能希望集成到ROS系统中的最简单和最常见的硬件之一:按钮。按钮是一个命令机器人完成下一个任务的输入设备,一个检测盒子是否打开的传感器,或一个重要的安全功能可以阻止电机超过关节限制。
在本教程中,我们将编写一个rosserial_arduino节点,该节点将监视引脚7上常关按钮的状态。每当按钮状态发生变化时,它将向主题“pushed”发布布尔消息。
1 硬件
在本教程中,您需要一个Arduino和某种通常关闭的瞬时开关或按钮。这microswitch from Sparkfun是一个不错的选择。
对于那些硬件设计的人,你会注意到有没有上拉电阻开关输入。这是因为Arduino的已经内置上拉电阻。引脚7被拉高,直到按钮被按下,并连接到地上。
2 程序
#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();
}
此代码是如何使用rosserial_arduino的典型示例。rosserial对象是全局声明的。
ros::NodeHandle nh;
std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);
在setup()函数中初始化
nh.initNode();
nh.advertise(pub_button);
然后在按钮状态改变时在“void loop()”中执行发布。
pub_button.publish(&pushed_msg);
2.1 监视按钮
此传感器不应传播有关按钮状态的消息,而应仅在按下或释放按钮时发布更新。要监视此更改,我们需要记住按钮的最后状态,并知道此状态有效的时间。然后,一旦状态发生变化,传感器应该去除抖动。它应该等待“足够长”,以便我们知道按钮值已经稳定并且没有抖动。这是因为在接触和释放期间机械触点来回反弹时,输入引脚上的电压将会反弹(如下图所示)。
在代码中,这个去抖动是在几个地方进行的。首先,有几个全局变量:存储按钮的最后一个值,读取引脚的时间,去除抖动的延迟时间以及,是否已发布。
17 bool last_reading ;
18 long last_debounce_time = 0 ;
19 long debounce_delay = 50 ;
20 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()中,代码在每个循环中读取按钮,检查按钮状态是否已更改,然后检查按钮状态是否稳定并已发布。
3 测试
运行:roscore
roscore
在新的终端窗口中,运行rosserial_python serial_node.py。确保使用正确的串行端口。
rostopic echo pushed
注意:摁下和放松是两个状态,分别对应于LED亮和灭,并对应于data为True和false。