Main Page
Classes
Class List
Class Members
All
a
b
f
g
h
i
l
m
n
o
p
r
s
t
u
v
z
~
Functions
Variables
b
h
i
l
m
n
o
p
r
s
t
u
v
z
Files
File List
File Members
All
Functions
src
simulator_node.cpp
Go to the documentation of this file.
1
#include "
ros/ros.h
"
2
3
#include "
mobile_robot_simulator/mobile_robot_simulator.h
"
4
#include "
mobile_robot_simulator/laser_simulator.h
"
5
6
int
main
(
int
argc,
char
**argv)
7
{
8
ros::init
(argc,argv,
"mobile_robot_simulator"
);
9
ros::NodeHandle
nh;
10
11
// global rate
12
float
rate = 10.0;
13
14
MobileRobotSimulator
mob_sim(&nh);
15
LaserScannerSimulator
laser_sim(&nh);
16
17
ROS_INFO
(
"--- Starting simulator"
);
18
19
ros::Duration
(1.0).
sleep
();
20
ros::AsyncSpinner
spinner
(2);
21
22
mob_sim.
publish_map_transform
=
true
;
23
mob_sim.
start
();
24
laser_sim.
start
();
25
26
ros::Time
tic =
ros::Time::now
();
27
28
spinner
.start();
29
while
(nh.
ok
() &&
ros::Time::now
()-tic<
ros::Duration
(10.0)) {
30
//ros::spinOnce();
31
ros::Duration
(0.01).
sleep
();
32
}
33
spinner
.stop();
34
35
ROS_INFO
(
"--- Stopping simulator"
);
36
37
mob_sim.
stop
();
38
laser_sim.
stop
();
39
40
tic =
ros::Time::now
();
41
while
(nh.
ok
() &&
ros::Time::now
()-tic<
ros::Duration
(5.0)) {
42
ros::spinOnce
();
43
ros::Duration
(0.01).
sleep
();
44
}
45
46
return
0;
47
48
}
// end main
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
LaserScannerSimulator::start
void start()
Definition:
laser_simulator.cpp:44
ros::AsyncSpinner
ros::spinOnce
ROSCPP_DECL void spinOnce()
mobile_robot_simulator.h
LaserScannerSimulator::stop
void stop()
Definition:
laser_simulator.cpp:52
MobileRobotSimulator::publish_map_transform
bool publish_map_transform
Definition:
mobile_robot_simulator.h:30
MobileRobotSimulator::stop
void stop()
Definition:
mobile_robot_simulator.cpp:57
spinner
void spinner()
LaserScannerSimulator
Definition:
laser_simulator.h:17
laser_simulator.h
ros::NodeHandle::ok
bool ok() const
main
int main(int argc, char **argv)
Definition:
simulator_node.cpp:6
ros::Time
ros::Duration::sleep
bool sleep() const
MobileRobotSimulator::start
void start()
Definition:
mobile_robot_simulator.cpp:49
ROS_INFO
#define ROS_INFO(...)
ros::Duration
ros::NodeHandle
MobileRobotSimulator
Definition:
mobile_robot_simulator.h:17
ros::Time::now
static Time now()
mobile_robot_simulator
Author(s): Mikkel Rath Pedersen
autogenerated on Thu Jun 2 2022 02:16:58