Public Member Functions | |
void | getParametersFromServer () |
LMS400Node (ros::NodeHandle &n) | |
void | restartMeasurementWithNewValues (float scanning_frequency, float angular_resolution, float min_angle, float diff_angle, int intensity, bool laser_enabled) |
bool | spin () |
int | start () |
int | stop () |
~LMS400Node () | |
Public Attributes | |
double | angular_resolution_ |
int | debug_ |
int | eRIS_ |
int | filter_ |
string | hostname_ |
bool | intensity_ |
bool | laser_enabled_ |
asr_sick_lms_400 | lms_ |
bool | loggedin_ |
double | max_angle_ |
int | mean_filter_params_ |
double | min_angle_ |
string | password_ |
int | port_ |
double | range_filter_params_max_ |
double | range_filter_params_min_ |
LaserScan | scan_ |
Publisher | scan_pub_ |
double | scanning_frequency_ |
Protected Attributes | |
ros::NodeHandle | nh_ |
Definition at line 54 of file lms400_node.cpp.
LMS400Node::LMS400Node | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 90 of file lms400_node.cpp.
LMS400Node::~LMS400Node | ( | ) | [inline] |
Definition at line 144 of file lms400_node.cpp.
void LMS400Node::getParametersFromServer | ( | ) | [inline] |
Definition at line 253 of file lms400_node.cpp.
void LMS400Node::restartMeasurementWithNewValues | ( | float | scanning_frequency, |
float | angular_resolution, | ||
float | min_angle, | ||
float | diff_angle, | ||
int | intensity, | ||
bool | laser_enabled | ||
) | [inline] |
Definition at line 226 of file lms400_node.cpp.
bool LMS400Node::spin | ( | ) | [inline] |
Definition at line 323 of file lms400_node.cpp.
int LMS400Node::start | ( | ) | [inline] |
Definition at line 152 of file lms400_node.cpp.
int LMS400Node::stop | ( | ) | [inline] |
Definition at line 210 of file lms400_node.cpp.
Definition at line 81 of file lms400_node.cpp.
Definition at line 87 of file lms400_node.cpp.
Definition at line 83 of file lms400_node.cpp.
Definition at line 70 of file lms400_node.cpp.
string LMS400Node::hostname_ |
Definition at line 66 of file lms400_node.cpp.
Definition at line 75 of file lms400_node.cpp.
Definition at line 78 of file lms400_node.cpp.
Definition at line 60 of file lms400_node.cpp.
Definition at line 86 of file lms400_node.cpp.
double LMS400Node::max_angle_ |
Definition at line 82 of file lms400_node.cpp.
Definition at line 71 of file lms400_node.cpp.
double LMS400Node::min_angle_ |
Definition at line 82 of file lms400_node.cpp.
ros::NodeHandle LMS400Node::nh_ [protected] |
Definition at line 57 of file lms400_node.cpp.
string LMS400Node::password_ |
Definition at line 66 of file lms400_node.cpp.
Definition at line 67 of file lms400_node.cpp.
Definition at line 72 of file lms400_node.cpp.
Definition at line 72 of file lms400_node.cpp.
LaserScan LMS400Node::scan_ |
Definition at line 61 of file lms400_node.cpp.
Definition at line 63 of file lms400_node.cpp.
Definition at line 81 of file lms400_node.cpp.