r2000_node.h
Go to the documentation of this file.
1 // Copyright (c) 2014, Pepperl+Fuchs GmbH, Mannheim
2 // Copyright (c) 2014, Denis Dillenberger
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without modification,
6 // are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice, this
9 // list of conditions and the following disclaimer.
10 //
11 // * Redistributions in binary form must reproduce the above copyright notice, this
12 // list of conditions and the following disclaimer in the documentation and/or
13 // other materials provided with the distribution.
14 //
15 // * Neither the name of Pepperl+Fuchs nor the names of its
16 // contributors may be used to endorse or promote products derived from
17 // this software without specific prior written permission.
18 //
19 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
23 // ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
26 // ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
28 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 
30 #ifndef R2000_NODE_H
31 #define R2000_NODE_H
32 
33 #include <ros/ros.h>
34 #include <std_msgs/String.h>
35 
36 namespace pepperl_fuchs {
37 class R2000Driver;
38 
41 class R2000Node
42 {
43 public:
45  R2000Node();
46 
48  void cmdMsgCallback( const std_msgs::StringConstPtr& msg );
49 
50 private:
53  bool connect();
54 
56  void getScanData( const ros::TimerEvent& e);
57 
60 
63 
66 
69 
71  std::string frame_id_;
72 
74  std::string scanner_ip_;
75 
78 
81 
84 };
85 }
86 
87 #endif // R2000_NODE_H
int scan_frequency_
scan_frequency parameter
Definition: r2000_node.h:77
Driver for the laserscanner R2000 of Pepperl+Fuchs.
Definition: r2000_driver.h:47
R2000Node()
Initialize and connect to laser range finder.
Definition: r2000_node.cpp:37
int samples_per_scan_
samples_per_scan parameter
Definition: r2000_node.h:80
ros::NodeHandle nh_
Internal ROS node handle.
Definition: r2000_node.h:59
void cmdMsgCallback(const std_msgs::StringConstPtr &msg)
Callback function for control commands.
Definition: r2000_node.cpp:145
ROS driver node for the Pepperl+Fuchs R2000 laser range finder.
Definition: r2000_node.h:41
void getScanData(const ros::TimerEvent &e)
Time callback function for getting data from the driver and sending them out.
Definition: r2000_node.cpp:106
std::string scanner_ip_
IP or hostname of laser range finder.
Definition: r2000_node.h:74
ros::Subscriber cmd_subscriber_
ROS subscriber for receiving control commands.
Definition: r2000_node.h:68
ros::Timer get_scan_data_timer_
Callback timer for getScanData(...)
Definition: r2000_node.h:62
ros::Publisher scan_publisher_
ROS publisher for publishing scan data.
Definition: r2000_node.h:65
R2000Driver * driver_
Pointer to driver.
Definition: r2000_node.h:83
std::string frame_id_
frame_id of sensor_msgs/Laserscan messages
Definition: r2000_node.h:71


pepperl_fuchs_r2000
Author(s): Denis Dillenberger
autogenerated on Mon Jun 10 2019 14:12:48