Go to the documentation of this file.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/planning_scene_monitor/planning_scene_monitor.h>
00038 #include <tf/transform_listener.h>
00039 #include <moveit/move_group/capability_names.h>
00040 #include <moveit/move_group/move_group_capability.h>
00041 #include <boost/algorithm/string/join.hpp>
00042 #include <boost/tokenizer.hpp>
00043 #include <moveit/macros/console_colors.h>
00044 #include <moveit/move_group/node_name.h>
00045 #include <set>
00046
00047 static const std::string ROBOT_DESCRIPTION =
00048 "robot_description";
00049
00050 namespace move_group
00051 {
00052 class MoveGroupExe
00053 {
00054 public:
00055 MoveGroupExe(const planning_scene_monitor::PlanningSceneMonitorPtr& psm, bool debug) : node_handle_("~")
00056 {
00057
00058 bool allow_trajectory_execution;
00059 node_handle_.param("allow_trajectory_execution", allow_trajectory_execution, true);
00060
00061 context_.reset(new MoveGroupContext(psm, allow_trajectory_execution, debug));
00062
00063
00064 configureCapabilities();
00065 }
00066
00067 ~MoveGroupExe()
00068 {
00069 capabilities_.clear();
00070 context_.reset();
00071 capability_plugin_loader_.reset();
00072 }
00073
00074 void status()
00075 {
00076 if (context_)
00077 {
00078 if (context_->status())
00079 {
00080 if (capabilities_.empty())
00081 printf(MOVEIT_CONSOLE_COLOR_BLUE "\nAll is well but no capabilities are loaded. There will be no party "
00082 ":(\n\n" MOVEIT_CONSOLE_COLOR_RESET);
00083 else
00084 printf(MOVEIT_CONSOLE_COLOR_GREEN "\nAll is well! Everyone is happy! You can start planning "
00085 "now!\n\n" MOVEIT_CONSOLE_COLOR_RESET);
00086 fflush(stdout);
00087 }
00088 }
00089 else
00090 ROS_ERROR("No MoveGroup context created. Nothing will work.");
00091 }
00092
00093 private:
00094 void configureCapabilities()
00095 {
00096 try
00097 {
00098 capability_plugin_loader_.reset(
00099 new pluginlib::ClassLoader<MoveGroupCapability>("moveit_ros_move_group", "move_group::MoveGroupCapability"));
00100 }
00101 catch (pluginlib::PluginlibException& ex)
00102 {
00103 ROS_FATAL_STREAM("Exception while creating plugin loader for move_group capabilities: " << ex.what());
00104 return;
00105 }
00106
00107 std::set<std::string> capabilities;
00108
00109
00110 for (size_t i = 0; i < sizeof(DEFAULT_CAPABILITIES) / sizeof(DEFAULT_CAPABILITIES[0]); ++i)
00111 capabilities.insert(DEFAULT_CAPABILITIES[i]);
00112
00113
00114 std::string capability_plugins;
00115 if (node_handle_.getParam("capabilities", capability_plugins))
00116 {
00117 boost::char_separator<char> sep(" ");
00118 boost::tokenizer<boost::char_separator<char> > tok(capability_plugins, sep);
00119 capabilities.insert(tok.begin(), tok.end());
00120 }
00121
00122
00123 if (node_handle_.getParam("disable_capabilities", capability_plugins))
00124 {
00125 boost::char_separator<char> sep(" ");
00126 boost::tokenizer<boost::char_separator<char> > tok(capability_plugins, sep);
00127 for (boost::tokenizer<boost::char_separator<char> >::iterator cap_name = tok.begin(); cap_name != tok.end();
00128 ++cap_name)
00129 capabilities.erase(*cap_name);
00130 }
00131
00132 for (std::set<std::string>::iterator plugin = capabilities.begin(); plugin != capabilities.end(); ++plugin)
00133 {
00134 try
00135 {
00136 printf(MOVEIT_CONSOLE_COLOR_CYAN "Loading '%s'...\n" MOVEIT_CONSOLE_COLOR_RESET, plugin->c_str());
00137 MoveGroupCapability* cap = capability_plugin_loader_->createUnmanagedInstance(*plugin);
00138 cap->setContext(context_);
00139 cap->initialize();
00140 capabilities_.push_back(MoveGroupCapabilityPtr(cap));
00141 }
00142 catch (pluginlib::PluginlibException& ex)
00143 {
00144 ROS_ERROR_STREAM("Exception while loading move_group capability '"
00145 << *plugin << "': " << ex.what() << std::endl
00146 << "Available capabilities: "
00147 << boost::algorithm::join(capability_plugin_loader_->getDeclaredClasses(), ", "));
00148 }
00149 }
00150
00151 std::stringstream ss;
00152 ss << std::endl;
00153 ss << std::endl;
00154 ss << "********************************************************" << std::endl;
00155 ss << "* MoveGroup using: " << std::endl;
00156 for (std::size_t i = 0; i < capabilities_.size(); ++i)
00157 ss << "* - " << capabilities_[i]->getName() << std::endl;
00158 ss << "********************************************************" << std::endl;
00159 ROS_INFO_STREAM(ss.str());
00160 }
00161
00162 ros::NodeHandle node_handle_;
00163 MoveGroupContextPtr context_;
00164 boost::shared_ptr<pluginlib::ClassLoader<MoveGroupCapability> > capability_plugin_loader_;
00165 std::vector<MoveGroupCapabilityPtr> capabilities_;
00166 };
00167 }
00168
00169 int main(int argc, char** argv)
00170 {
00171 ros::init(argc, argv, move_group::NODE_NAME);
00172
00173 ros::AsyncSpinner spinner(1);
00174 spinner.start();
00175
00176 boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener(ros::Duration(10.0)));
00177
00178 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor(
00179 new planning_scene_monitor::PlanningSceneMonitor(ROBOT_DESCRIPTION, tf));
00180
00181 if (planning_scene_monitor->getPlanningScene())
00182 {
00183 bool debug = false;
00184 for (int i = 1; i < argc; ++i)
00185 if (strncmp(argv[i], "--debug", 7) == 0)
00186 {
00187 debug = true;
00188 break;
00189 }
00190 if (debug)
00191 ROS_INFO("MoveGroup debug mode is ON");
00192 else
00193 ROS_INFO("MoveGroup debug mode is OFF");
00194
00195 printf(MOVEIT_CONSOLE_COLOR_CYAN "Starting context monitors...\n" MOVEIT_CONSOLE_COLOR_RESET);
00196 planning_scene_monitor->startSceneMonitor();
00197 planning_scene_monitor->startWorldGeometryMonitor();
00198 planning_scene_monitor->startStateMonitor();
00199 printf(MOVEIT_CONSOLE_COLOR_CYAN "Context monitors started.\n" MOVEIT_CONSOLE_COLOR_RESET);
00200
00201 move_group::MoveGroupExe mge(planning_scene_monitor, debug);
00202
00203 planning_scene_monitor->publishDebugInformation(debug);
00204
00205 mge.status();
00206
00207 ros::waitForShutdown();
00208 }
00209 else
00210 ROS_ERROR("Planning scene not configured");
00211
00212 return 0;
00213 }