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>
57 int main(
int argc,
char** argv)
64 boost::program_options::options_description desc;
65 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
67 "DB.")(
"port", boost::program_options::value<std::size_t>(),
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)");
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);
81 if (vm.count(
"help") || (!vm.count(
"scene") && !vm.count(
"constraint") && !vm.count(
"state")))
83 std::cout << desc << std::endl;
88 delay = vm[
"delay"].as<
double>();
92 std::cout << desc << std::endl;
96 auto db_loader = std::make_unique<warehouse_ros::DatabaseLoader>();
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())
107 ros::Publisher pub_scene, pub_req, pub_res, pub_constr, pub_state;
111 if (vm.count(
"scene"))
114 bool req = vm.count(
"planning_requests");
115 bool res = vm.count(
"planning_results");
124 std::vector<std::string> scene_names;
125 pss.getPlanningSceneNames(vm[
"scene"].as<std::string>(), scene_names);
127 for (
const std::string& scene_name : scene_names)
130 if (pss.getPlanningScene(pswm, scene_name))
134 pub_scene.
publish(
static_cast<const moveit_msgs::PlanningScene&
>(*pswm));
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());
145 for (std::size_t i = 0; i < planning_queries.size(); ++i)
149 ROS_INFO(
"Publishing query '%s'", query_names[i].c_str());
150 pub_req.
publish(
static_cast<const moveit_msgs::MotionPlanRequest&
>(*planning_queries[i]));
155 std::vector<moveit_warehouse::RobotTrajectoryWithMetadata> planning_results;
156 pss.getPlanningResults(planning_results, query_names[i], pswm->name);
159 pub_res.
publish(
static_cast<const moveit_msgs::RobotTrajectory&
>(*planning_result));
171 if (vm.count(
"constraint"))
175 std::vector<std::string> cnames;
178 for (
const std::string& cname : cnames)
183 ROS_INFO(
"Publishing constraints '%s'",
185 pub_constr.
publish(
static_cast<const moveit_msgs::Constraints&
>(*cwm));
193 if (vm.count(
"state"))
197 std::vector<std::string> rnames;
200 for (
const std::string& rname : rnames)
206 pub_state.
publish(
static_cast<const moveit_msgs::RobotState&
>(*rswm));