moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
40 #include <boost/program_options/cmdline.hpp>
41 #include <boost/program_options/options_description.hpp>
42 #include <boost/program_options/parsers.hpp>
43 #include <boost/program_options/variables_map.hpp>
44 #include <rclcpp/executors/static_single_threaded_executor.hpp>
45 #include <rclcpp/logger.hpp>
46 #include <rclcpp/logging.hpp>
47 #include <rclcpp/node.hpp>
48 #include <rclcpp/node_options.hpp>
49 #include <rclcpp/publisher.hpp>
50 #include <rclcpp/qos_event.hpp>
51 #include <rclcpp/rate.hpp>
52 #include <rclcpp/utilities.hpp>
53 
54 static const std::string PLANNING_SCENE_TOPIC = "planning_scene";
55 static const std::string PLANNING_REQUEST_TOPIC = "motion_plan_request";
56 static const std::string PLANNING_RESULTS_TOPIC = "motion_plan_results";
57 
58 static const std::string CONSTRAINTS_TOPIC = "constraints";
59 
60 static const std::string STATES_TOPIC = "robot_states";
61 
62 using namespace std::chrono_literals;
63 
64 int main(int argc, char** argv)
65 {
66  rclcpp::init(argc, argv);
67  rclcpp::NodeOptions node_options;
68  node_options.allow_undeclared_parameters(true);
69  node_options.automatically_declare_parameters_from_overrides(true);
70  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("publish_warehouse_data", node_options);
71  const auto logger = node->get_logger();
72 
73  // time to wait in between publishing messages
74  double delay = 0.001;
75 
76  // clang-format off
77  boost::program_options::options_description desc;
78  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
79  "Host for the "
80  "DB.")("port", boost::program_options::value<std::size_t>(),
81  "Port for the DB.")(
82  "scene", boost::program_options::value<std::string>(), "Name of scene to publish.")(
83  "planning_requests", "Also publish the planning requests that correspond to the scene")(
84  "planning_results", "Also publish the planning results that correspond to the scene")(
85  "constraint", boost::program_options::value<std::string>(), "Name of constraint to publish.")(
86  "state", boost::program_options::value<std::string>(),
87  "Name of the robot state to publish.")("delay", boost::program_options::value<double>()->default_value(delay),
88  "Time to wait in between publishing messages (s)");
89  // clang-format on
90  boost::program_options::variables_map vm;
91  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
92  boost::program_options::notify(vm);
93 
94  if (vm.count("help") || (!vm.count("scene") && !vm.count("constraint") && !vm.count("state")))
95  {
96  std::cout << desc << '\n';
97  return 1;
98  }
99  try
100  {
101  delay = vm["delay"].as<double>();
102  }
103  catch (...)
104  {
105  std::cout << desc << '\n';
106  return 2;
107  }
108  // Set up db
109  warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase(node);
110  if (vm.count("host") && vm.count("port"))
111  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
112  if (!conn->connect())
113  return 1;
114 
115  rclcpp::executors::StaticSingleThreadedExecutor executor;
116  executor.add_node(node);
117 
118  rclcpp::Rate rate((int64_t)delay * 1000ms);
119 
120  // publish the scene
121  if (vm.count("scene"))
122  {
123  auto pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>(PLANNING_SCENE_TOPIC, 10);
124  bool req = vm.count("planning_requests");
125  bool res = vm.count("planning_results");
126 
128  executor.spin_once(0ns);
129 
130  std::vector<std::string> scene_names;
131  pss.getPlanningSceneNames(vm["scene"].as<std::string>(), scene_names);
132 
133  for (const std::string& scene_name : scene_names)
134  {
136  if (pss.getPlanningScene(pswm, scene_name))
137  {
138  RCLCPP_INFO(logger, "Publishing scene '%s'",
140  pub_scene->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
141  executor.spin_once(0ns);
142 
143  // publish optional data associated to the scene
144  if (req || res)
145  {
146  auto pub_req = node->create_publisher<moveit_msgs::msg::MotionPlanRequest>(PLANNING_REQUEST_TOPIC, 100);
147  auto pub_res = node->create_publisher<moveit_msgs::msg::RobotTrajectory>(PLANNING_RESULTS_TOPIC, 100);
148  std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
149  std::vector<std::string> query_names;
150  pss.getPlanningQueries(planning_queries, query_names, pswm->name);
151  RCLCPP_INFO(logger, "There are %d planning queries associated to the scene",
152  static_cast<int>(planning_queries.size()));
153  rclcpp::sleep_for(500ms);
154  for (std::size_t i = 0; i < planning_queries.size(); ++i)
155  {
156  if (req)
157  {
158  RCLCPP_INFO(logger, "Publishing query '%s'", query_names[i].c_str());
159  pub_req->publish(static_cast<const moveit_msgs::msg::MotionPlanRequest&>(*planning_queries[i]));
160  executor.spin_once(0ns);
161  }
162  if (res)
163  {
164  std::vector<moveit_warehouse::RobotTrajectoryWithMetadata> planning_results;
165  pss.getPlanningResults(planning_results, query_names[i], pswm->name);
166  for (moveit_warehouse::RobotTrajectoryWithMetadata& planning_result : planning_results)
167  {
168  pub_res->publish(static_cast<const moveit_msgs::msg::RobotTrajectory&>(*planning_result));
169  executor.spin_once(0ns);
170  }
171  }
172  }
173  }
174  rate.sleep();
175  }
176  }
177  }
178 
179  // publish constraints
180  if (vm.count("constraint"))
181  {
183  auto pub_constr = node->create_publisher<moveit_msgs::msg::Constraints>(CONSTRAINTS_TOPIC, 100);
184  std::vector<std::string> cnames;
185  cs.getKnownConstraints(vm["constraint"].as<std::string>(), cnames);
186 
187  for (const std::string& cname : cnames)
188  {
190  if (cs.getConstraints(cwm, cname))
191  {
192  RCLCPP_INFO(logger, "Publishing constraints '%s'",
194  pub_constr->publish(static_cast<const moveit_msgs::msg::Constraints&>(*cwm));
195  executor.spin_once(0ns);
196  rate.sleep();
197  }
198  }
199  }
200 
201  // publish constraints
202  if (vm.count("state"))
203  {
205  auto pub_state = node->create_publisher<moveit_msgs::msg::RobotState>(STATES_TOPIC, 100);
206  std::vector<std::string> rnames;
207  rs.getKnownRobotStates(vm["state"].as<std::string>(), rnames);
208 
209  for (const std::string& rname : rnames)
210  {
212  if (rs.getRobotState(rswm, rname))
213  {
214  RCLCPP_INFO(logger, "Publishing state '%s'",
215  rswm->lookupString(moveit_warehouse::RobotStateStorage::STATE_NAME).c_str());
216  pub_state->publish(static_cast<const moveit_msgs::msg::RobotState&>(*rswm));
217  executor.spin_once(0ns);
218  rate.sleep();
219  }
220  }
221  }
222 
223  rclcpp::sleep_for(1s);
224  RCLCPP_INFO(logger, "Done.");
225 
226  return 0;
227 }
int main(int argc, char **argv)
Definition: broadcast.cpp:64
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.
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
static const std::string CONSTRAINTS_ID_NAME
void getPlanningResults(std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::msg::MotionPlanRequest &planning_query) const
void getPlanningQueries(std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const
void getPlanningSceneNames(std::vector< std::string > &names) const
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_name.
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
static const std::string STATE_NAME
Definition: state_storage.h:57
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
Definition: state_storage.h:47
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr RobotTrajectoryWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest