r2000_node.h
Go to the documentation of this file.
00001 // Copyright (c) 2014, Pepperl+Fuchs GmbH, Mannheim
00002 // Copyright (c) 2014, Denis Dillenberger
00003 // All rights reserved.
00004 //
00005 // Redistribution and use in source and binary forms, with or without modification,
00006 // are permitted provided that the following conditions are met:
00007 //
00008 // * Redistributions of source code must retain the above copyright notice, this
00009 //   list of conditions and the following disclaimer.
00010 //
00011 // * Redistributions in binary form must reproduce the above copyright notice, this
00012 //   list of conditions and the following disclaimer in the documentation and/or
00013 //   other materials provided with the distribution.
00014 //
00015 // * Neither the name of Pepperl+Fuchs nor the names of its
00016 //   contributors may be used to endorse or promote products derived from
00017 //   this software without specific prior written permission.
00018 //
00019 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
00023 // ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
00026 // ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 #ifndef R2000_NODE_H
00031 #define R2000_NODE_H
00032 
00033 #include <ros/ros.h>
00034 #include <std_msgs/String.h>
00035 
00036 namespace pepperl_fuchs {
00037 class R2000Driver;
00038 
00041 class R2000Node
00042 {
00043 public:
00045     R2000Node();
00046 
00048     void cmdMsgCallback( const std_msgs::StringConstPtr& msg );
00049 
00050 private:
00053     bool connect();
00054 
00056     void getScanData( const ros::TimerEvent& e);
00057 
00059     ros::NodeHandle nh_;
00060 
00062     ros::Timer get_scan_data_timer_;
00063 
00065     ros::Publisher scan_publisher_;
00066 
00068     ros::Subscriber cmd_subscriber_;
00069 
00071     std::string frame_id_;
00072 
00074     std::string scanner_ip_;
00075 
00077     int scan_frequency_;
00078 
00080     int samples_per_scan_;
00081 
00083     R2000Driver* driver_;
00084 };
00085 }
00086 
00087 #endif // R2000_NODE_H


pepperl_fuchs_r2000
Author(s): Denis Dillenberger
autogenerated on Sat Sep 17 2016 04:01:08