18 #ifndef LASERSCANNER_LMS400_H 19 #define LASERSCANNER_LMS400_H 22 #include <sick_lms400.h> 36 void newData(
const sensor_msgs::LaserScan::ConstPtr& msg);
57 #endif // LASERSCANNER_LMS400_H sensor_msgs::LaserScan::Ptr msg_ptr
LaserScanner_LMS400(std::string hostname, int framerate)
static constexpr float SCANNER_TARGET_RESOLUTION
static constexpr float SCANNER_ANGLE_SPREAD
static constexpr float SCANNER_STARTING_ANGLE
void newData(const sensor_msgs::LaserScan::ConstPtr &msg)
float scanner_actual_resolution
asr_sick_lms_400::asr_sick_lms_400 sickLMS400
float scanner_max_resolution