Main Page
Classes
Files
File List
File Members
src
Laserscanner
laserscanner_mild.cpp
Go to the documentation of this file.
1
18
#include "
Laserscanner/laserscanner_mild.h
"
19
20
Laserscanner_MILD::Laserscanner_MILD
() :
Abstract_LaserScanner
()
21
{
22
calibration_starting_angle
= -90;
23
calibration_angle_spread
= 180;
24
calibration_scan_values
= 360;
25
}
26
27
void
Laserscanner_MILD::laserScanCallback
(
const
sensor_msgs::LaserScan::ConstPtr& msg)
28
{
29
newData
(msg);
30
}
31
32
void
Laserscanner_MILD::run
()
33
{
34
active
=
true
;
35
ros::NodeHandle
n;
36
a
= n.
subscribe
(
"scan"
, 1000, &
Laserscanner_MILD::laserScanCallback
,
this
);
37
while
(
active
)
38
{
39
ros::spinOnce
();
40
}
41
n.
shutdown
();
42
std::cout <<
"Scanner stopped..."
<< std::endl;
43
}
44
45
void
Laserscanner_MILD::stop
()
46
{
47
active
=
false
;
48
}
Laserscanner_MILD::stop
void stop()
Definition:
laserscanner_mild.cpp:45
Abstract_LaserScanner::calibration_scan_values
int calibration_scan_values
Definition:
abstract_laserscanner.h:34
ros::NodeHandle
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Laserscanner_MILD::run
void run()
Definition:
laserscanner_mild.cpp:32
Laserscanner_MILD::newData
void newData(const sensor_msgs::LaserScan::ConstPtr &msg)
Abstract_LaserScanner
Definition:
abstract_laserscanner.h:25
Abstract_LaserScanner::calibration_starting_angle
float calibration_starting_angle
Definition:
abstract_laserscanner.h:32
Laserscanner_MILD::Laserscanner_MILD
Laserscanner_MILD()
Definition:
laserscanner_mild.cpp:20
Laserscanner_MILD::laserScanCallback
void laserScanCallback(const sensor_msgs::LaserScan::ConstPtr &msg)
Definition:
laserscanner_mild.cpp:27
ros::NodeHandle::shutdown
void shutdown()
ros::spinOnce
ROSCPP_DECL void spinOnce()
Laserscanner_MILD::active
bool active
Definition:
laserscanner_mild.h:35
Laserscanner_MILD::a
ros::Subscriber a
Definition:
laserscanner_mild.h:36
laserscanner_mild.h
Abstract_LaserScanner::calibration_angle_spread
float calibration_angle_spread
Definition:
abstract_laserscanner.h:33
asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43