00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/warehouse/planning_scene_storage.h>
00038 #include <moveit/warehouse/constraints_storage.h>
00039 #include <moveit/warehouse/state_storage.h>
00040 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00041 #include <boost/algorithm/string/join.hpp>
00042 #include <boost/program_options/cmdline.hpp>
00043 #include <boost/program_options/options_description.hpp>
00044 #include <boost/program_options/parsers.hpp>
00045 #include <boost/program_options/variables_map.hpp>
00046 #include <ros/ros.h>
00047
00048 static const std::string ROBOT_DESCRIPTION = "robot_description";
00049
00050 void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor* psm, moveit_warehouse::PlanningSceneStorage* pss)
00051 {
00052 ROS_INFO("Received an update to the planning scene...");
00053
00054 if (!psm->getPlanningScene()->getName().empty())
00055 {
00056 if (!pss->hasPlanningScene(psm->getPlanningScene()->getName()))
00057 {
00058 moveit_msgs::PlanningScene psmsg;
00059 psm->getPlanningScene()->getPlanningSceneMsg(psmsg);
00060 pss->addPlanningScene(psmsg);
00061 }
00062 else
00063 ROS_INFO("Scene '%s' was previously added. Not adding again.", psm->getPlanningScene()->getName().c_str());
00064 }
00065 else
00066 ROS_INFO("Scene name is empty. Not saving.");
00067 }
00068
00069 void onMotionPlanRequest(const moveit_msgs::MotionPlanRequestConstPtr& req,
00070 planning_scene_monitor::PlanningSceneMonitor* psm, moveit_warehouse::PlanningSceneStorage* pss)
00071 {
00072 if (psm->getPlanningScene()->getName().empty())
00073 {
00074 ROS_INFO("Scene name is empty. Not saving planning request.");
00075 return;
00076 }
00077 pss->addPlanningQuery(*req, psm->getPlanningScene()->getName());
00078 }
00079
00080 void onConstraints(const moveit_msgs::ConstraintsConstPtr& msg, moveit_warehouse::ConstraintsStorage* cs)
00081 {
00082 if (msg->name.empty())
00083 {
00084 ROS_INFO("No name specified for constraints. Not saving.");
00085 return;
00086 }
00087
00088 if (cs->hasConstraints(msg->name))
00089 {
00090 ROS_INFO("Replacing constraints '%s'", msg->name.c_str());
00091 cs->removeConstraints(msg->name);
00092 cs->addConstraints(*msg);
00093 }
00094 else
00095 {
00096 ROS_INFO("Adding constraints '%s'", msg->name.c_str());
00097 cs->addConstraints(*msg);
00098 }
00099 }
00100
00101 void onRobotState(const moveit_msgs::RobotStateConstPtr& msg, moveit_warehouse::RobotStateStorage* rs)
00102 {
00103 std::vector<std::string> names;
00104 rs->getKnownRobotStates(names);
00105 std::set<std::string> names_set(names.begin(), names.end());
00106 std::size_t n = names.size();
00107 while (names_set.find("S" + boost::lexical_cast<std::string>(n)) != names_set.end())
00108 n++;
00109 std::string name = "S" + boost::lexical_cast<std::string>(n);
00110 ROS_INFO("Adding robot state '%s'", name.c_str());
00111 rs->addRobotState(*msg, name);
00112 }
00113
00114 int main(int argc, char** argv)
00115 {
00116 ros::init(argc, argv, "save_to_warehouse", ros::init_options::AnonymousName);
00117
00118 boost::program_options::options_description desc;
00119 desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(), "Host for the "
00120 "DB.")(
00121 "port", boost::program_options::value<std::size_t>(), "Port for the DB.");
00122
00123 boost::program_options::variables_map vm;
00124 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
00125 boost::program_options::notify(vm);
00126
00127 if (vm.count("help"))
00128 {
00129 std::cout << desc << std::endl;
00130 return 1;
00131 }
00132
00133 warehouse_ros::DatabaseConnection::Ptr conn = moveit_warehouse::loadDatabase();
00134 if (vm.count("host") && vm.count("port"))
00135 conn->setParams(vm["host"].as<std::string>(), vm["port"].as<std::size_t>());
00136 if (!conn->connect())
00137 return 1;
00138
00139 ros::AsyncSpinner spinner(1);
00140 spinner.start();
00141
00142 ros::NodeHandle nh;
00143 boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener());
00144 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION, tf);
00145 if (!psm.getPlanningScene())
00146 {
00147 ROS_ERROR("Unable to initialize PlanningSceneMonitor");
00148 return 1;
00149 }
00150
00151 psm.startSceneMonitor();
00152 psm.startWorldGeometryMonitor();
00153 moveit_warehouse::PlanningSceneStorage pss(conn);
00154 moveit_warehouse::ConstraintsStorage cs(conn);
00155 moveit_warehouse::RobotStateStorage rs(conn);
00156 std::vector<std::string> names;
00157 pss.getPlanningSceneNames(names);
00158 if (names.empty())
00159 ROS_INFO("There are no previously stored scenes");
00160 else
00161 {
00162 ROS_INFO("Previously stored scenes:");
00163 for (std::size_t i = 0; i < names.size(); ++i)
00164 ROS_INFO(" * %s", names[i].c_str());
00165 }
00166 cs.getKnownConstraints(names);
00167 if (names.empty())
00168 ROS_INFO("There are no previously stored constraints");
00169 else
00170 {
00171 ROS_INFO("Previously stored constraints:");
00172 for (std::size_t i = 0; i < names.size(); ++i)
00173 ROS_INFO(" * %s", names[i].c_str());
00174 }
00175 rs.getKnownRobotStates(names);
00176 if (names.empty())
00177 ROS_INFO("There are no previously stored robot states");
00178 else
00179 {
00180 ROS_INFO("Previously stored robot states:");
00181 for (std::size_t i = 0; i < names.size(); ++i)
00182 ROS_INFO(" * %s", names[i].c_str());
00183 }
00184
00185 psm.addUpdateCallback(boost::bind(&onSceneUpdate, &psm, &pss));
00186
00187 boost::function<void(const moveit_msgs::MotionPlanRequestConstPtr&)> callback1 =
00188 boost::bind(&onMotionPlanRequest, _1, &psm, &pss);
00189 ros::Subscriber mplan_req_sub = nh.subscribe("motion_plan_request", 100, callback1);
00190 boost::function<void(const moveit_msgs::ConstraintsConstPtr&)> callback2 = boost::bind(&onConstraints, _1, &cs);
00191 ros::Subscriber constr_sub = nh.subscribe("constraints", 100, callback2);
00192 boost::function<void(const moveit_msgs::RobotStateConstPtr&)> callback3 = boost::bind(&onRobotState, _1, &rs);
00193 ros::Subscriber state_sub = nh.subscribe("robot_state", 100, callback3);
00194
00195 std::vector<std::string> topics;
00196 psm.getMonitoredTopics(topics);
00197 ROS_INFO_STREAM("Listening for scene updates on topics " << boost::algorithm::join(topics, ", "));
00198 ROS_INFO_STREAM("Listening for planning requests on topic " << mplan_req_sub.getTopic());
00199 ROS_INFO_STREAM("Listening for named constraints on topic " << constr_sub.getTopic());
00200 ROS_INFO_STREAM("Listening for states on topic " << state_sub.getTopic());
00201
00202 ros::waitForShutdown();
00203 return 0;
00204 }