36 #include <sensor_msgs/LaserScan.h> 37 #include <boost/asio.hpp> 39 #include <std_msgs/UInt16.h> 41 int main(
int argc,
char **argv)
43 ros::init(argc, argv,
"neato_laser_publisher");
52 std_msgs::UInt16 rpms;
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);
59 boost::asio::io_service io;
67 sensor_msgs::LaserScan::Ptr scan(
new sensor_msgs::LaserScan);
68 scan->header.frame_id = frame_id;
73 motor_pub.publish(rpms);
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());
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.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
uint16_t rpms
RPMS derived from the rpm bytes in an XV11 packet.
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...