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>
54 ROS_INFO(
"Received an update to the planning scene...");
60 moveit_msgs::PlanningScene psmsg;
68 ROS_INFO(
"Scene name is empty. Not saving.");
76 ROS_INFO(
"Scene name is empty. Not saving planning request.");
86 ROS_INFO(
"No name specified for constraints. Not saving.");
92 ROS_INFO(
"Replacing constraints '%s'", msg.name.c_str());
98 ROS_INFO(
"Adding constraints '%s'", msg.name.c_str());
105 std::vector<std::string> 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())
111 std::string
name =
"S" + boost::lexical_cast<std::string>(n);
116 int main(
int argc,
char** argv)
120 boost::program_options::options_description desc;
121 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
123 "DB.")(
"port", boost::program_options::value<std::size_t>(),
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);
130 if (vm.count(
"help"))
132 std::cout << desc << std::endl;
136 auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
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())
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);
153 ROS_ERROR(
"Unable to initialize PlanningSceneMonitor");
162 std::vector<std::string> names;
165 ROS_INFO(
"There are no previously stored scenes");
168 ROS_INFO(
"Previously stored scenes:");
169 for (
const std::string&
name : names)
174 ROS_INFO(
"There are no previously stored constraints");
177 ROS_INFO(
"Previously stored constraints:");
178 for (
const std::string&
name : names)
183 ROS_INFO(
"There are no previously stored robot states");
186 ROS_INFO(
"Previously stored robot states:");
187 for (
const std::string&
name : names)
194 "motion_plan_request", 100, [&psm, &pss](
const auto& req) {
onMotionPlanRequest(*req, psm, pss); });
197 "constraints", 100, [&cs](
const auto& constraints) {
return onConstraints(*constraints, cs); });
203 std::vector<std::string> topics;
204 psm.getMonitoredTopics(topics);
205 ROS_INFO_STREAM(
"Listening for scene updates on topics " << boost::algorithm::join(topics,
", "));
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());