collision_monitor_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
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 }


cob_collision_monitor
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 21:22:41