Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <ros/ros.h>
00036 #include <sensor_msgs/LaserScan.h>
00037 #include <boost/asio.hpp>
00038 #include <xv_11_laser_driver/xv11_laser.h>
00039 #include <std_msgs/UInt16.h>
00040
00041 int main(int argc, char **argv)
00042 {
00043 ros::init(argc, argv, "neato_laser_publisher");
00044 ros::NodeHandle n;
00045 ros::NodeHandle priv_nh("~");
00046
00047 std::string port;
00048 int baud_rate;
00049 std::string frame_id;
00050 int firmware_number;
00051
00052 std_msgs::UInt16 rpms;
00053
00054 priv_nh.param("port", port, std::string("/dev/ttyUSB0"));
00055 priv_nh.param("baud_rate", baud_rate, 115200);
00056 priv_nh.param("frame_id", frame_id, std::string("neato_laser"));
00057 priv_nh.param("firmware_version", firmware_number, 1);
00058
00059 boost::asio::io_service io;
00060
00061 try {
00062 xv_11_laser_driver::XV11Laser laser(port, baud_rate, firmware_number, io);
00063 ros::Publisher laser_pub = n.advertise<sensor_msgs::LaserScan>("scan", 1000);
00064 ros::Publisher motor_pub = n.advertise<std_msgs::UInt16>("rpms",1000);
00065
00066 while (ros::ok()) {
00067 sensor_msgs::LaserScan::Ptr scan(new sensor_msgs::LaserScan);
00068 scan->header.frame_id = frame_id;
00069 scan->header.stamp = ros::Time::now();
00070 laser.poll(scan);
00071 rpms.data=laser.rpms;
00072 laser_pub.publish(scan);
00073 motor_pub.publish(rpms);
00074
00075 }
00076 laser.close();
00077 return 0;
00078 } catch (boost::system::system_error ex) {
00079 ROS_ERROR("Error instantiating laser object. Are you sure you have the correct port and baud rate? Error was %s", ex.what());
00080 return -1;
00081 }
00082 }