laserscanner_mild.cpp
Go to the documentation of this file.
00001 
00018 #include "Laserscanner/laserscanner_mild.h"
00019 
00020 Laserscanner_MILD::Laserscanner_MILD() : Abstract_LaserScanner()
00021 {
00022     calibration_starting_angle = -90;
00023     calibration_angle_spread = 180;
00024     calibration_scan_values = 360;
00025 }
00026 
00027 void Laserscanner_MILD::laserScanCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
00028 {
00029     newData(msg);
00030 }
00031 
00032 void Laserscanner_MILD::run()
00033 {
00034     active = true;
00035     ros::NodeHandle n;
00036     a = n.subscribe("scan", 1000, &Laserscanner_MILD::laserScanCallback, this);
00037     while (active)
00038     {
00039         ros::spinOnce();
00040     }
00041     n.shutdown();
00042     std::cout << "Scanner stopped..." << std::endl;
00043 }
00044 
00045 void Laserscanner_MILD::stop()
00046 {
00047     active = false;
00048 }


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Thu Jun 6 2019 21:22:44