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