neato_laser_publisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Eric Perko, Chad Rockey
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Case Western Reserve University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ros/ros.h>
36 #include <sensor_msgs/LaserScan.h>
37 #include <boost/asio.hpp>
39 #include <std_msgs/UInt16.h>
40 
41 int main(int argc, char **argv)
42 {
43  ros::init(argc, argv, "neato_laser_publisher");
45  ros::NodeHandle priv_nh("~");
46 
47  std::string port;
48  int baud_rate;
49  std::string frame_id;
50  int firmware_number;
51 
52  std_msgs::UInt16 rpms;
53 
54  priv_nh.param("port", port, std::string("/dev/ttyUSB0"));
55  priv_nh.param("baud_rate", baud_rate, 115200);
56  priv_nh.param("frame_id", frame_id, std::string("neato_laser"));
57  priv_nh.param("firmware_version", firmware_number, 2);
58 
59  boost::asio::io_service io;
60 
61  try {
62  xv_11_laser_driver::XV11Laser laser(port, baud_rate, firmware_number, io);
63  ros::Publisher laser_pub = n.advertise<sensor_msgs::LaserScan>("scan", 1000);
64  ros::Publisher motor_pub = n.advertise<std_msgs::UInt16>("rpms",1000);
65 
66  while (ros::ok()) {
67  sensor_msgs::LaserScan::Ptr scan(new sensor_msgs::LaserScan);
68  scan->header.frame_id = frame_id;
69  scan->header.stamp = ros::Time::now();
70  laser.poll(scan);
71  rpms.data=laser.rpms;
72  laser_pub.publish(scan);
73  motor_pub.publish(rpms);
74 
75  }
76  laser.close();
77  return 0;
78  } catch (boost::system::system_error ex) {
79  ROS_ERROR("Error instantiating laser object. Are you sure you have the correct port and baud rate? Error was %s", ex.what());
80  return -1;
81  }
82 }
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void close()
Close the driver down and prevent the polling loop from advancing.
Definition: xv11_laser.h:66
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
uint16_t rpms
RPMS derived from the rpm bytes in an XV11 packet.
Definition: xv11_laser.h:43
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void poll(sensor_msgs::LaserScan::Ptr scan)
Poll the laser to get a new scan. Blocks until a complete new scan is received or close is called...
Definition: xv11_laser.cpp:43
static Time now()
#define ROS_ERROR(...)


xv_11_laser_driver
Author(s): Eric Perko, Chad Rockey, Rohan Agrawal, Steve 'dillo Okay
autogenerated on Mon Jun 10 2019 15:48:10