ROS driver node for the Pepperl+Fuchs R2000 laser range finder. More...
#include <r2000_node.h>
Public Member Functions | |
void | cmdMsgCallback (const std_msgs::StringConstPtr &msg) |
Callback function for control commands. More... | |
R2000Node () | |
Initialize and connect to laser range finder. More... | |
Private Member Functions | |
bool | connect () |
void | getScanData (const ros::TimerEvent &e) |
Time callback function for getting data from the driver and sending them out. More... | |
Private Attributes | |
ros::Subscriber | cmd_subscriber_ |
ROS subscriber for receiving control commands. More... | |
R2000Driver * | driver_ |
Pointer to driver. More... | |
std::string | frame_id_ |
frame_id of sensor_msgs/Laserscan messages More... | |
ros::Timer | get_scan_data_timer_ |
Callback timer for getScanData(...) More... | |
ros::NodeHandle | nh_ |
Internal ROS node handle. More... | |
int | samples_per_scan_ |
samples_per_scan parameter More... | |
int | scan_frequency_ |
scan_frequency parameter More... | |
ros::Publisher | scan_publisher_ |
ROS publisher for publishing scan data. More... | |
std::string | scanner_ip_ |
IP or hostname of laser range finder. More... | |
ROS driver node for the Pepperl+Fuchs R2000 laser range finder.
Definition at line 41 of file r2000_node.h.
pepperl_fuchs::R2000Node::R2000Node | ( | ) |
Initialize and connect to laser range finder.
Definition at line 37 of file r2000_node.cpp.
void pepperl_fuchs::R2000Node::cmdMsgCallback | ( | const std_msgs::StringConstPtr & | msg | ) |
Callback function for control commands.
Definition at line 145 of file r2000_node.cpp.
|
private |
Connect to the laser range finder
Definition at line 64 of file r2000_node.cpp.
|
private |
Time callback function for getting data from the driver and sending them out.
Definition at line 106 of file r2000_node.cpp.
|
private |
ROS subscriber for receiving control commands.
Definition at line 68 of file r2000_node.h.
|
private |
Pointer to driver.
Definition at line 83 of file r2000_node.h.
|
private |
frame_id of sensor_msgs/Laserscan messages
Definition at line 71 of file r2000_node.h.
|
private |
Callback timer for getScanData(...)
Definition at line 62 of file r2000_node.h.
|
private |
Internal ROS node handle.
Definition at line 59 of file r2000_node.h.
|
private |
samples_per_scan parameter
Definition at line 80 of file r2000_node.h.
|
private |
scan_frequency parameter
Definition at line 77 of file r2000_node.h.
|
private |
ROS publisher for publishing scan data.
Definition at line 65 of file r2000_node.h.
|
private |
IP or hostname of laser range finder.
Definition at line 74 of file r2000_node.h.