Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include "valid_state_publisher.h"
00019
00020
00021 int main(int argc, char **argv)
00022 {
00023 ros::init (argc, argv, "collision_monitor_node");
00024
00025 ros::NodeHandle nh("~");
00026
00027 boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener(ros::Duration(nh.param("max_cache_time", 2.0))));
00028 planning_scene_monitor::PlanningSceneMonitorPtr psm(new planning_scene_monitor::PlanningSceneMonitor("robot_description", tf));
00029
00030 double state_update_frequency;
00031 if(nh.getParam("state_update_frequency", state_update_frequency))
00032 psm->setStateUpdateFrequency(state_update_frequency);
00033
00034 if(nh.param("start_scene_monitor", true))
00035 psm->startSceneMonitor();
00036 if(nh.param("start_world_geometry_monitor", true))
00037 psm->startWorldGeometryMonitor();
00038 psm->startStateMonitor();
00039
00040 cob_collision_monitor::ValidStatePublisher vsp(nh, psm);
00041
00042 ros::spin();
00043
00044 return 0;
00045 }