Main Page
Related Pages
Modules
Namespaces
Classes
Files
File List
File Members
mvsim_node_src
mvsim_node_main.cpp
Go to the documentation of this file.
1
4
#include "
mvsim/mvsim_node_core.h
"
5
6
/*------------------------------------------------------------------------------
7
* main()
8
* Main function to set up ROS node.
9
*----------------------------------------------------------------------------*/
10
11
int
main
(
int
argc,
char
** argv)
12
{
13
// Set up ROS.
14
ros::init
(argc, argv,
"mvsim"
);
15
ros::NodeHandle
n
;
16
17
// Create a "Node" object.
18
MVSimNode
node(n);
19
20
// Declare variables that can be modified by launch file or command line.
21
int
rate;
22
std::string world_file;
23
24
// Initialize node parameters from launch file or command line.
25
// Use a private node handle so that multiple instances of the node can be
26
// run simultaneously
27
// while using different parameters.
28
ros::NodeHandle
private_node_handle_(
"~"
);
29
private_node_handle_.
param
(
"simul_rate"
, rate, 100);
30
private_node_handle_.
param
(
"world_file"
, world_file, std::string(
""
));
31
32
// Init world model:
33
if
(!world_file.empty()) node.
loadWorldModel
(world_file);
34
35
// Set up a dynamic reconfigure server.
36
// Do this before parameter server, else some of the parameter server
37
// values can be overwritten.
38
dynamic_reconfigure::Server<mvsim::mvsimNodeConfig> dr_srv;
39
dynamic_reconfigure::Server<mvsim::mvsimNodeConfig>::CallbackType cb;
40
cb = boost::bind(&
MVSimNode::configCallback
, &node, _1, _2);
41
dr_srv.setCallback(cb);
42
43
// Create a publisher and name the topic.
44
// ros::Publisher pub_message =
45
// n.advertise<node_example::NodeExampleData>("example", 10);
46
// Name the topic, message queue, callback function with class name, and
47
// object containing callback function.
48
// ros::Subscriber sub_message = n.subscribe("example", 1000,
49
// &NodeExample::messageCallback, node_example);
50
51
// Tell ROS how fast to run this node.
52
ros::Rate
r
(rate);
53
54
// Main loop.
55
while
(n.
ok
())
56
{
57
node.
spin
();
58
ros::spinOnce
();
59
r.
sleep
();
60
}
61
62
return
0;
63
64
}
// end main()
ros::NodeHandle
MVSimNode
Definition:
mvsim_node_core.h:36
ros::init
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Rate
n
GLsizei n
MVSimNode::loadWorldModel
void loadWorldModel(const std::string &world_xml_file)
Definition:
mvsim_node.cpp:80
MVSimNode::spin
void spin()
Process pending msgs, run real-time simulation, etc.
Definition:
mvsim_node.cpp:125
MVSimNode::configCallback
void configCallback(mvsim::mvsimNodeConfig &config, uint32_t level)
Definition:
mvsim_node.cpp:113
ros::NodeHandle::param
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
main
int main(int argc, char **argv)
Definition:
mvsim_node_main.cpp:11
ros::Rate::sleep
bool sleep()
r
GLdouble GLdouble GLdouble r
ros::NodeHandle::ok
bool ok() const
ros::spinOnce
ROSCPP_DECL void spinOnce()
mvsim_node_core.h
mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:51