save_to_warehouse.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 #include <boost/algorithm/string/join.hpp>
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 #include <ros/ros.h>
49 
50 static const std::string ROBOT_DESCRIPTION = "robot_description";
51 
53 {
54  ROS_INFO("Received an update to the planning scene...");
55 
56  if (!psm.getPlanningScene()->getName().empty())
57  {
58  if (!pss.hasPlanningScene(psm.getPlanningScene()->getName()))
59  {
60  moveit_msgs::PlanningScene psmsg;
61  psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
62  pss.addPlanningScene(psmsg);
63  }
64  else
65  ROS_INFO("Scene '%s' was previously added. Not adding again.", psm.getPlanningScene()->getName().c_str());
66  }
67  else
68  ROS_INFO("Scene name is empty. Not saving.");
69 }
70 
71 void onMotionPlanRequest(const moveit_msgs::MotionPlanRequest& req, planning_scene_monitor::PlanningSceneMonitor& psm,
73 {
74  if (psm.getPlanningScene()->getName().empty())
75  {
76  ROS_INFO("Scene name is empty. Not saving planning request.");
77  return;
78  }
79  pss.addPlanningQuery(req, psm.getPlanningScene()->getName());
80 }
81 
82 void onConstraints(const moveit_msgs::Constraints& msg, moveit_warehouse::ConstraintsStorage& cs)
83 {
84  if (msg.name.empty())
85  {
86  ROS_INFO("No name specified for constraints. Not saving.");
87  return;
88  }
89 
90  if (cs.hasConstraints(msg.name))
91  {
92  ROS_INFO("Replacing constraints '%s'", msg.name.c_str());
93  cs.removeConstraints(msg.name);
94  cs.addConstraints(msg);
95  }
96  else
97  {
98  ROS_INFO("Adding constraints '%s'", msg.name.c_str());
99  cs.addConstraints(msg);
100  }
101 }
102 
103 void onRobotState(const moveit_msgs::RobotState& msg, moveit_warehouse::RobotStateStorage& rs)
104 {
105  std::vector<std::string> names;
106  rs.getKnownRobotStates(names);
107  std::set<std::string> names_set(names.begin(), names.end());
108  std::size_t n = names.size();
109  while (names_set.find("S" + boost::lexical_cast<std::string>(n)) != names_set.end())
110  n++;
111  std::string name = "S" + boost::lexical_cast<std::string>(n);
112  ROS_INFO("Adding robot state '%s'", name.c_str());
113  rs.addRobotState(msg, name);
114 }
115 
116 int main(int argc, char** argv)
117 {
118  ros::init(argc, argv, "save_to_warehouse", ros::init_options::AnonymousName);
119 
120  boost::program_options::options_description desc;
121  desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
122  "Host for the "
123  "DB.")("port", boost::program_options::value<std::size_t>(),
124  "Port for the DB.");
125 
126  boost::program_options::variables_map vm;
127  boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
128  boost::program_options::notify(vm);
129 
130  if (vm.count("help"))
131  {
132  std::cout << desc << std::endl;
133  return 1;
134  }
135  // Set up db
136  auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
137  warehouse_ros::DatabaseConnection::Ptr conn = db_loader->loadDatabase();
138  if (vm.count("host") && vm.count("port"))
139  conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
140  if (!conn->connect())
141  return 1;
142 
144  spinner.start();
145 
146  ros::NodeHandle nh;
147  std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::make_shared<tf2_ros::Buffer>();
148  std::shared_ptr<tf2_ros::TransformListener> tf_listener =
149  std::make_shared<tf2_ros::TransformListener>(*tf_buffer, nh);
151  if (!psm.getPlanningScene())
152  {
153  ROS_ERROR("Unable to initialize PlanningSceneMonitor");
154  return 1;
155  }
156 
157  psm.startSceneMonitor();
162  std::vector<std::string> names;
163  pss.getPlanningSceneNames(names);
164  if (names.empty())
165  ROS_INFO("There are no previously stored scenes");
166  else
167  {
168  ROS_INFO("Previously stored scenes:");
169  for (const std::string& name : names)
170  ROS_INFO(" * %s", name.c_str());
171  }
172  cs.getKnownConstraints(names);
173  if (names.empty())
174  ROS_INFO("There are no previously stored constraints");
175  else
176  {
177  ROS_INFO("Previously stored constraints:");
178  for (const std::string& name : names)
179  ROS_INFO(" * %s", name.c_str());
180  }
181  rs.getKnownRobotStates(names);
182  if (names.empty())
183  ROS_INFO("There are no previously stored robot states");
184  else
185  {
186  ROS_INFO("Previously stored robot states:");
187  for (const std::string& name : names)
188  ROS_INFO(" * %s", name.c_str());
189  }
190 
191  psm.addUpdateCallback([&psm, &pss](auto&& /*unused*/) { return onSceneUpdate(psm, pss); });
192 
193  ros::Subscriber mplan_req_sub = nh.subscribe<moveit_msgs::MotionPlanRequest>(
194  "motion_plan_request", 100, [&psm, &pss](const auto& req) { onMotionPlanRequest(*req, psm, pss); });
195 
196  ros::Subscriber constr_sub = nh.subscribe<moveit_msgs::Constraints>(
197  "constraints", 100, [&cs](const auto& constraints) { return onConstraints(*constraints, cs); });
198 
199  ros::Subscriber state_sub = nh.subscribe<moveit_msgs::RobotState>("robot_state", 100, [&rs](const auto& state) {
200  return onRobotState(*state, rs);
201  });
202 
203  std::vector<std::string> topics;
204  psm.getMonitoredTopics(topics);
205  ROS_INFO_STREAM("Listening for scene updates on topics " << boost::algorithm::join(topics, ", "));
206  ROS_INFO_STREAM("Listening for planning requests on topic " << mplan_req_sub.getTopic());
207  ROS_INFO_STREAM("Listening for named constraints on topic " << constr_sub.getTopic());
208  ROS_INFO_STREAM("Listening for states on topic " << state_sub.getTopic());
209 
211  return 0;
212 }
ros::init_options::AnonymousName
AnonymousName
boost::shared_ptr
planning_scene_monitor::PlanningSceneMonitor::addUpdateCallback
void addUpdateCallback(const boost::function< void(SceneUpdateType)> &fn)
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)
onMotionPlanRequest
void onMotionPlanRequest(const moveit_msgs::MotionPlanRequest &req, planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
Definition: save_to_warehouse.cpp:71
ros.h
moveit_warehouse::RobotStateStorage::addRobotState
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
Definition: state_storage.cpp:67
state_storage.h
onConstraints
void onConstraints(const moveit_msgs::Constraints &msg, moveit_warehouse::ConstraintsStorage &cs)
Definition: save_to_warehouse.cpp:82
ros::AsyncSpinner
ros::Subscriber::getTopic
std::string getTopic() const
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
moveit_warehouse::ConstraintsStorage
Definition: constraints_storage.h:82
moveit_warehouse::PlanningSceneStorage::addPlanningScene
void addPlanningScene(const moveit_msgs::PlanningScene &scene)
Definition: planning_scene_storage.cpp:73
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
planning_scene_monitor::PlanningSceneMonitor
onSceneUpdate
void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
Definition: save_to_warehouse.cpp:52
database_loader.h
spinner
void spinner()
moveit_warehouse::ConstraintsStorage::removeConstraints
void removeConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
Definition: constraints_storage.cpp:157
name
std::string name
moveit_warehouse::PlanningSceneStorage::addPlanningQuery
void addPlanningQuery(const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
Definition: planning_scene_storage.cpp:132
planning_scene_monitor.h
planning_scene_storage.h
constraints_storage.h
ROS_ERROR
#define ROS_ERROR(...)
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::ConstraintsStorage::addConstraints
void addConstraints(const moveit_msgs::Constraints &msg, const std::string &robot="", const std::string &group="")
Definition: constraints_storage.cpp:68
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
onRobotState
void onRobotState(const moveit_msgs::RobotState &msg, moveit_warehouse::RobotStateStorage &rs)
Definition: save_to_warehouse.cpp:103
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: save_to_warehouse.cpp:50
planning_scene_monitor::PlanningSceneMonitor::startWorldGeometryMonitor
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
moveit_warehouse::ConstraintsStorage::hasConstraints
bool hasConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
Definition: constraints_storage.cpp:85
transform_listener.h
main
int main(int argc, char **argv)
Definition: save_to_warehouse.cpp:116
tf_buffer
tf2_ros::Buffer * tf_buffer
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames
void getPlanningSceneNames(std::vector< std::string > &names) const
Definition: planning_scene_storage.cpp:186
ROS_INFO
#define ROS_INFO(...)
moveit_warehouse::PlanningSceneStorage::hasPlanningScene
bool hasPlanningScene(const std::string &name) const
Definition: planning_scene_storage.cpp:87
ros::NodeHandle
ros::Subscriber


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