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> 56 int main(
int argc,
char** argv)
63 boost::program_options::options_description desc;
64 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
"Host for the " 66 "port", boost::program_options::value<std::size_t>(),
67 "Port for the DB.")(
"scene", boost::program_options::value<std::string>(),
"Name of scene to publish.")(
68 "planning_requests",
"Also publish the planning requests that correspond to the scene")(
69 "planning_results",
"Also publish the planning results that correspond to the scene")(
70 "constraint", boost::program_options::value<std::string>(),
"Name of constraint to publish.")(
71 "state", boost::program_options::value<std::string>(),
72 "Name of the robot state to publish.")(
"delay", boost::program_options::value<double>()->default_value(delay),
73 "Time to wait in between publishing messages (s)");
75 boost::program_options::variables_map vm;
76 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
77 boost::program_options::notify(vm);
79 if (vm.count(
"help") || (!vm.count(
"scene") && !vm.count(
"constraint") && !vm.count(
"state")))
81 std::cout << desc << std::endl;
86 delay = vm[
"delay"].as<
double>();
90 std::cout << desc << std::endl;
95 if (vm.count(
"host") && vm.count(
"port"))
96 conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
104 ros::Publisher pub_scene, pub_req, pub_res, pub_constr, pub_state;
108 if (vm.count(
"scene"))
111 bool req = vm.count(
"planning_requests");
112 bool res = vm.count(
"planning_results");
121 std::vector<std::string> scene_names;
122 pss.getPlanningSceneNames(vm[
"scene"].as<std::string>(), scene_names);
124 for (std::size_t i = 0; i < scene_names.size(); ++i)
127 if (pss.getPlanningScene(pswm, scene_names[i]))
131 pub_scene.
publish(static_cast<const moveit_msgs::PlanningScene&>(*pswm));
137 std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
138 std::vector<std::string> query_names;
139 pss.getPlanningQueries(planning_queries, query_names, pswm->name);
140 ROS_INFO(
"There are %d planning queries associated to the scene", (
int)planning_queries.size());
142 for (std::size_t i = 0; i < planning_queries.size(); ++i)
146 ROS_INFO(
"Publishing query '%s'", query_names[i].c_str());
147 pub_req.
publish(static_cast<const moveit_msgs::MotionPlanRequest&>(*planning_queries[i]));
152 std::vector<moveit_warehouse::RobotTrajectoryWithMetadata> planning_results;
153 pss.getPlanningResults(planning_results, query_names[i], pswm->name);
154 for (std::size_t j = 0; j < planning_results.size(); ++j)
156 pub_res.
publish(static_cast<const moveit_msgs::RobotTrajectory&>(*planning_results[j]));
168 if (vm.count(
"constraint"))
172 std::vector<std::string> cnames;
175 for (std::size_t i = 0; i < cnames.size(); ++i)
180 ROS_INFO(
"Publishing constraints '%s'",
182 pub_constr.
publish(static_cast<const moveit_msgs::Constraints&>(*cwm));
190 if (vm.count(
"state"))
194 std::vector<std::string> rnames;
197 for (std::size_t i = 0; i < rnames.size(); ++i)
203 pub_state.
publish(static_cast<const moveit_msgs::RobotState&>(*rswm));
static const std::string PLANNING_SCENE_TOPIC
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
int main(int argc, char **argv)
static const std::string PLANNING_REQUEST_TOPIC
static const std::string STATES_TOPIC
warehouse_ros::DatabaseConnection::Ptr loadDatabase()
Load a database connection.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
static const std::string CONSTRAINTS_TOPIC
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.
static const std::string CONSTRAINTS_ID_NAME
static const std::string STATE_NAME
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
ROSCPP_DECL void spinOnce()
static const std::string PLANNING_SCENE_ID_NAME
static const std::string PLANNING_RESULTS_TOPIC