broadcast.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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 
41 
42 #include <boost/program_options/cmdline.hpp>
43 #include <boost/program_options/options_description.hpp>
44 #include <boost/program_options/parsers.hpp>
45 #include <boost/program_options/variables_map.hpp>
46 
47 #include <ros/ros.h>
48 
49 static const std::string PLANNING_SCENE_TOPIC = "planning_scene";
50 static const std::string PLANNING_REQUEST_TOPIC = "motion_plan_request";
51 static const std::string PLANNING_RESULTS_TOPIC = "motion_plan_results";
52 
53 static const std::string CONSTRAINTS_TOPIC = "constraints";
54 
55 static const std::string STATES_TOPIC = "robot_states";
56 
57 int main(int argc, char** argv)
58 {
59  ros::init(argc, argv, "publish_warehouse_data", ros::init_options::AnonymousName);
60 
61  // time to wait in between publishing messages
62  double delay = 0.001;
63 
64  boost::program_options::options_description desc;
65  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
66  "Host for the "
67  "DB.")("port", boost::program_options::value<std::size_t>(),
68  "Port for the DB.")(
69  "scene", boost::program_options::value<std::string>(), "Name of scene to publish.")(
70  "planning_requests", "Also publish the planning requests that correspond to the scene")(
71  "planning_results", "Also publish the planning results that correspond to the scene")(
72  "constraint", boost::program_options::value<std::string>(), "Name of constraint to publish.")(
73  "state", boost::program_options::value<std::string>(),
74  "Name of the robot state to publish.")("delay", boost::program_options::value<double>()->default_value(delay),
75  "Time to wait in between publishing messages (s)");
76 
77  boost::program_options::variables_map vm;
78  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
79  boost::program_options::notify(vm);
80 
81  if (vm.count("help") || (!vm.count("scene") && !vm.count("constraint") && !vm.count("state")))
82  {
83  std::cout << desc << std::endl;
84  return 1;
85  }
86  try
87  {
88  delay = vm["delay"].as<double>();
89  }
90  catch (...)
91  {
92  std::cout << desc << std::endl;
93  return 2;
94  }
95  // Set up db
96  auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
97  warehouse_ros::DatabaseConnection::Ptr conn = db_loader->loadDatabase();
98  if (vm.count("host") && vm.count("port"))
99  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
100  if (!conn->connect())
101  return 1;
102 
104  spinner.start();
105 
106  ros::NodeHandle nh;
107  ros::Publisher pub_scene, pub_req, pub_res, pub_constr, pub_state;
108  ros::Duration wait_time(delay);
109 
110  // publish the scene
111  if (vm.count("scene"))
112  {
113  pub_scene = nh.advertise<moveit_msgs::PlanningScene>(PLANNING_SCENE_TOPIC, 10);
114  bool req = vm.count("planning_requests");
115  bool res = vm.count("planning_results");
116  if (req)
117  pub_req = nh.advertise<moveit_msgs::MotionPlanRequest>(PLANNING_REQUEST_TOPIC, 100);
118  if (res)
119  pub_res = nh.advertise<moveit_msgs::RobotTrajectory>(PLANNING_RESULTS_TOPIC, 100);
120 
122  ros::spinOnce();
123 
124  std::vector<std::string> scene_names;
125  pss.getPlanningSceneNames(vm["scene"].as<std::string>(), scene_names);
126 
127  for (const std::string& scene_name : scene_names)
128  {
130  if (pss.getPlanningScene(pswm, scene_name))
131  {
132  ROS_INFO("Publishing scene '%s'",
134  pub_scene.publish(static_cast<const moveit_msgs::PlanningScene&>(*pswm));
135  ros::spinOnce();
136 
137  // publish optional data associated to the scene
138  if (req || res)
139  {
140  std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
141  std::vector<std::string> query_names;
142  pss.getPlanningQueries(planning_queries, query_names, pswm->name);
143  ROS_INFO("There are %d planning queries associated to the scene", (int)planning_queries.size());
144  ros::WallDuration(0.5).sleep();
145  for (std::size_t i = 0; i < planning_queries.size(); ++i)
146  {
147  if (req)
148  {
149  ROS_INFO("Publishing query '%s'", query_names[i].c_str());
150  pub_req.publish(static_cast<const moveit_msgs::MotionPlanRequest&>(*planning_queries[i]));
151  ros::spinOnce();
152  }
153  if (res)
154  {
155  std::vector<moveit_warehouse::RobotTrajectoryWithMetadata> planning_results;
156  pss.getPlanningResults(planning_results, query_names[i], pswm->name);
157  for (moveit_warehouse::RobotTrajectoryWithMetadata& planning_result : planning_results)
158  {
159  pub_res.publish(static_cast<const moveit_msgs::RobotTrajectory&>(*planning_result));
160  ros::spinOnce();
161  }
162  }
163  }
164  }
165  wait_time.sleep();
166  }
167  }
168  }
169 
170  // publish constraints
171  if (vm.count("constraint"))
172  {
174  pub_constr = nh.advertise<moveit_msgs::Constraints>(CONSTRAINTS_TOPIC, 100);
175  std::vector<std::string> cnames;
176  cs.getKnownConstraints(vm["constraint"].as<std::string>(), cnames);
177 
178  for (const std::string& cname : cnames)
179  {
181  if (cs.getConstraints(cwm, cname))
182  {
183  ROS_INFO("Publishing constraints '%s'",
185  pub_constr.publish(static_cast<const moveit_msgs::Constraints&>(*cwm));
186  ros::spinOnce();
187  wait_time.sleep();
188  }
189  }
190  }
191 
192  // publish constraints
193  if (vm.count("state"))
194  {
196  pub_state = nh.advertise<moveit_msgs::RobotState>(STATES_TOPIC, 100);
197  std::vector<std::string> rnames;
198  rs.getKnownRobotStates(vm["state"].as<std::string>(), rnames);
199 
200  for (const std::string& rname : rnames)
201  {
203  if (rs.getRobotState(rswm, rname))
204  {
205  ROS_INFO("Publishing state '%s'", rswm->lookupString(moveit_warehouse::RobotStateStorage::STATE_NAME).c_str());
206  pub_state.publish(static_cast<const moveit_msgs::RobotState&>(*rswm));
207  ros::spinOnce();
208  wait_time.sleep();
209  }
210  }
211  }
212 
213  ros::WallDuration(1.0).sleep();
214  ROS_INFO("Done.");
215 
216  return 0;
217 }
ros::init_options::AnonymousName
AnonymousName
ros::WallDuration::sleep
bool sleep() const
PLANNING_REQUEST_TOPIC
static const std::string PLANNING_REQUEST_TOPIC
Definition: broadcast.cpp:50
ros::Publisher
PLANNING_RESULTS_TOPIC
static const std::string PLANNING_RESULTS_TOPIC
Definition: broadcast.cpp:51
boost::shared_ptr
moveit_warehouse::RobotStateStorage
Definition: state_storage.h:82
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
state_storage.h
STATES_TOPIC
static const std::string STATES_TOPIC
Definition: broadcast.cpp:55
ros::AsyncSpinner
ros::spinOnce
ROSCPP_DECL void spinOnce()
moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME
static const std::string CONSTRAINTS_ID_NAME
Definition: constraints_storage.h:87
moveit_warehouse::ConstraintsStorage
Definition: constraints_storage.h:82
moveit_warehouse::ConstraintsStorage::getKnownConstraints
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
Definition: constraints_storage.cpp:106
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
database_loader.h
spinner
void spinner()
main
int main(int argc, char **argv)
Definition: broadcast.cpp:57
planning_scene_storage.h
constraints_storage.h
moveit_warehouse::PlanningSceneStorage
Definition: planning_scene_storage.h:89
moveit_warehouse::RobotStateStorage::getKnownRobotStates
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
Definition: state_storage.cpp:100
moveit_warehouse::RobotStateStorage::STATE_NAME
static const std::string STATE_NAME
Definition: state_storage.h:87
CONSTRAINTS_TOPIC
static const std::string CONSTRAINTS_TOPIC
Definition: broadcast.cpp:53
moveit_warehouse::ConstraintsStorage::getConstraints
bool getConstraints(ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
Definition: constraints_storage.cpp:121
ros::Duration::sleep
bool sleep() const
PLANNING_SCENE_TOPIC
static const std::string PLANNING_SCENE_TOPIC
Definition: broadcast.cpp:49
ros::WallDuration
ROS_INFO
#define ROS_INFO(...)
moveit_warehouse::RobotStateStorage::getRobotState
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
Definition: state_storage.cpp:113
ros::Duration
moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME
static const std::string PLANNING_SCENE_ID_NAME
Definition: planning_scene_storage.h:94
ros::NodeHandle


warehouse
Author(s): Ioan Sucan
autogenerated on Mon May 27 2024 02:28:07