ROS与Arduino-IR Ranger(红外测距仪)
IR Ranger(红外测距仪)
说明
- 这个教程展示通过Arduino和rosserial使用红外测距仪
- 使用sharp IR Ranger 红外测距仪
硬件
- Arduino
- sharp IR Ranger 或其他
连接图
- 确保连接到模拟插脚0
代码
/*
* rosserial IR Ranger Example
*
* This example is calibrated for the Sharp GP2D120XJ00F.
*/
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range( "range_data", &range_msg);
const int analog_pin = 0;
unsigned long range_timer;
/*
* getRange() - samples the analog input from the ranger
* and converts it into meters.
*/
float getRange(int pin_num){
int sample;
// Get data
sample = analogRead(pin_num)/4;
// if the ADC reading is too low,
// then we are really far away from anything
if(sample < 10)
return 254; // max range
// Magic numbers to get cm
sample= 1309/(sample-3);
return (sample - 1)/100; //convert to meters
}
char frameid[] = "/ir_ranger";
void setup()
{
nh.initNode();
nh.advertise(pub_range);
range_msg.radiation_type = sensor_msgs::Range::INFRARED;
range_msg.header.frame_id = frameid;
range_msg.field_of_view = 0.01;
range_msg.min_range = 0.03;
range_msg.max_range = 0.4;
}
void loop()
{
// publish the range value every 50 milliseconds
// since it takes that long for the sensor to stabilize
if ( (millis()-range_timer) > 50){
range_msg.range = getRange(analog_pin);
range_msg.header.stamp = nh.now();
pub_range.publish(&range_msg);
range_timer = millis();
}
nh.spinOnce();
}
代码解释
- 代码
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range( "range_data", &range_msg);
解释:
- 必需包含的头文件
- 实例化节点处理类
- 实例化发布对象
- 代码
const int analog_pin = 0;
unsigned long range_timer;
/*
* getRange() - samples the analog input from the ranger
* and converts it into meters.
*/
float getRange(int pin_num){
int sample;
// Get data
sample = analogRead(pin_num)/4;
// if the ADC reading is too low,
// then we are really far away from anything
if(sample < 10)
return 254; // max range
// Magic numbers to get cm
sample= 1309/(sample-3);
return (sample - 1)/100; //convert to meters
}
解释:
- 定义连接的引脚
- 创建定时器变量
- 创建函数用于转换模拟信号为对应的以米计量的距离。
- 代码
char frameid[] = "/ir_ranger";
解释:
- 创建全局可用的参考系ID
- 代码
void setup()
{
nh.initNode();
nh.advertise(pub_range);
range_msg.radiation_type = sensor_msgs::Range::INFRARED;
range_msg.header.frame_id = frameid;
range_msg.field_of_view = 0.01;
range_msg.min_range = 0.03;
range_msg.max_range = 0.4;
}
解释:
- Arduino的setup函数,初始变量
- 代码
void loop()
{
// publish the range value every 50 milliseconds
// since it takes that long for the sensor to stabilize
if ( (millis()-range_timer) > 50){
range_msg.range = getRange(analog_pin);
range_msg.header.stamp = nh.now();
pub_range.publish(&range_msg);
range_timer = millis();
}
nh.spinOnce();
}
解释:
- Arduino的loop函数,每50毫秒发布一次红外数据
测试
- 新窗口打开
$roscore
- 新窗口打开,/dev/ttyUSB0为设备端口号
$ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
- 新窗口打开,用rxplot来可视化红外数据
$ rxplot range_data/range
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号