publish_scene_from_text.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Ioan A. Sucan nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
38 
39 int main(int argc, char **argv)
40 {
41  ros::init(argc, argv, "publish_planning_scene", ros::init_options::AnonymousName);
42 
43  // decide whether to publish the full scene
44  bool full_scene = false;
45 
46  // the index of the argument with the filename
47  int filename_index = 1;
48  if (argc > 2)
49  if (strncmp(argv[1], "--scene", 7) == 0)
50  {
51  full_scene = true;
52  filename_index = 2;
53  }
54 
55  if (argc > 1)
56  {
58  spinner.start();
59 
60  ros::NodeHandle nh;
61  ros::Publisher pub_scene;
62  if (full_scene)
63  pub_scene = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
64  else
65  pub_scene = nh.advertise<moveit_msgs::PlanningSceneWorld>("planning_scene_world", 1);
66 
68  opt.robot_description_ = "robot_description";
69  opt.load_kinematics_solvers_ = false;
70  robot_model_loader::RobotModelLoaderPtr rml(new robot_model_loader::RobotModelLoader(opt));
71  planning_scene::PlanningScene ps(rml->getModel());
72 
73  std::ifstream f(argv[filename_index]);
74  if (f.good() && !f.eof())
75  {
76  ROS_INFO("Publishing geometry from '%s' ...", argv[filename_index]);
77  ps.loadGeometryFromStream(f);
78  moveit_msgs::PlanningScene ps_msg;
79  ps.getPlanningSceneMsg(ps_msg);
80  ps_msg.is_diff = true;
81 
82  ros::WallDuration dt(0.5);
83  unsigned int attempts = 0;
84  ROS_WARN("Waiting for the subscriber %d", pub_scene.getNumSubscribers());
85  while (pub_scene.getNumSubscribers() < 1 && ++attempts < 100) {
86  ROS_WARN("Waiting for the subscriber");
87  dt.sleep();
88  }
89 
90  if (full_scene)
91  pub_scene.publish(ps_msg);
92  else
93  pub_scene.publish(ps_msg.world);
94 
95  sleep(1);
96  }
97  else
98  ROS_WARN("Unable to load '%s'.", argv[filename_index]);
99  }
100  else
101  ROS_WARN("A filename was expected as argument. That file should be a text representation of the geometry in a planning scene.");
102 
103  ros::shutdown();
104  return 0;
105 }
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
void spinner()
bool sleep() const
#define ROS_INFO(...)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
opt
ROSCPP_DECL void shutdown()


vs060
Author(s): Ryohei Ueda
autogenerated on Mon Jun 10 2019 13:13:22