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
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00038
00039 int main(int argc, char **argv)
00040 {
00041 ros::init(argc, argv, "publish_planning_scene", ros::init_options::AnonymousName);
00042
00043
00044 bool full_scene = false;
00045
00046
00047 int filename_index = 1;
00048 if (argc > 2)
00049 if (strncmp(argv[1], "--scene", 7) == 0)
00050 {
00051 full_scene = true;
00052 filename_index = 2;
00053 }
00054
00055 if (argc > 1)
00056 {
00057 ros::AsyncSpinner spinner(1);
00058 spinner.start();
00059
00060 ros::NodeHandle nh;
00061 ros::Publisher pub_scene;
00062 if (full_scene)
00063 pub_scene = nh.advertise<moveit_msgs::PlanningScene>(planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC, 1);
00064 else
00065 pub_scene = nh.advertise<moveit_msgs::PlanningSceneWorld>(planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC, 1);
00066
00067 robot_model_loader::RobotModelLoader::Options opt;
00068 opt.robot_description_ = "robot_description";
00069 opt.load_kinematics_solvers_ = false;
00070 robot_model_loader::RobotModelLoaderPtr rml(new robot_model_loader::RobotModelLoader(opt));
00071 planning_scene::PlanningScene ps(rml->getModel());
00072
00073 std::ifstream f(argv[filename_index]);
00074 if (f.good() && !f.eof())
00075 {
00076 ROS_INFO("Publishing geometry from '%s' ...", argv[filename_index]);
00077 ps.loadGeometryFromStream(f);
00078 moveit_msgs::PlanningScene ps_msg;
00079 ps.getPlanningSceneMsg(ps_msg);
00080 ps_msg.is_diff = true;
00081
00082 ros::WallDuration dt(0.5);
00083 unsigned int attempts = 0;
00084 while (pub_scene.getNumSubscribers() < 1 && ++attempts < 100)
00085 dt.sleep();
00086
00087 if (full_scene)
00088 pub_scene.publish(ps_msg);
00089 else
00090 pub_scene.publish(ps_msg.world);
00091
00092 sleep(1);
00093 }
00094 else
00095 ROS_WARN("Unable to load '%s'.", argv[filename_index]);
00096 }
00097 else
00098 ROS_WARN("A filename was expected as argument. That file should be a text representation of the geometry in a planning scene.");
00099
00100 ros::shutdown();
00101 return 0;
00102 }