move_group.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00038 #include <tf/transform_listener.h>
00039 #include <moveit/move_group/move_group_capability.h>
00040 #include <boost/algorithm/string/join.hpp>
00041 #include <boost/tokenizer.hpp>
00042 #include <moveit/macros/console_colors.h>
00043 #include <moveit/move_group/node_name.h>
00044 
00045 static const std::string ROBOT_DESCRIPTION = "robot_description";    // name of the robot description (a param name, so it can be changed externally)
00046 
00047 namespace move_group
00048 {
00049 
00050 class MoveGroupExe
00051 {
00052 public:
00053 
00054   MoveGroupExe(const planning_scene_monitor::PlanningSceneMonitorPtr& psm, bool debug) :
00055     node_handle_("~")
00056   {
00057     // if the user wants to be able to disable execution of paths, they can just set this ROS param to false
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     // start the capabilities
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 :(\n\n" MOVEIT_CONSOLE_COLOR_RESET);
00082         else
00083           printf(MOVEIT_CONSOLE_COLOR_GREEN "\nAll is well! Everyone is happy! You can start planning now!\n\n" MOVEIT_CONSOLE_COLOR_RESET);
00084         fflush(stdout);
00085       }
00086     }
00087     else
00088       ROS_ERROR("No MoveGroup context created. Nothing will work.");
00089   }
00090 
00091 private:
00092 
00093   void configureCapabilities()
00094   {
00095     try
00096     {
00097       capability_plugin_loader_.reset(new pluginlib::ClassLoader<MoveGroupCapability>("moveit_ros_move_group", "move_group::MoveGroupCapability"));
00098     }
00099     catch(pluginlib::PluginlibException& ex)
00100     {
00101       ROS_FATAL_STREAM("Exception while creating plugin loader for move_group capabilities: " << ex.what());
00102       return;
00103     }
00104 
00105     // add individual capabilities move_group supports
00106     std::string capability_plugins;
00107     if (node_handle_.getParam("capabilities", capability_plugins))
00108     {
00109       boost::char_separator<char> sep(" ");
00110       boost::tokenizer<boost::char_separator<char> > tok(capability_plugins, sep);
00111       for(boost::tokenizer<boost::char_separator<char> >::iterator beg = tok.begin() ; beg != tok.end(); ++beg)
00112       {
00113         std::string plugin = *beg;
00114         try
00115         {
00116           MoveGroupCapability *cap = capability_plugin_loader_->createUnmanagedInstance(plugin);
00117           cap->setContext(context_);
00118           cap->initialize();
00119           capabilities_.push_back(boost::shared_ptr<MoveGroupCapability>(cap));
00120         }
00121         catch(pluginlib::PluginlibException& ex)
00122         {
00123           ROS_ERROR_STREAM("Exception while loading move_group capability '" << plugin << "': " << ex.what() << std::endl
00124                            << "Available capabilities: " << boost::algorithm::join(capability_plugin_loader_->getDeclaredClasses(), ", "));
00125         }
00126       }
00127     }
00128     std::stringstream ss;
00129     ss << std::endl;
00130     ss << "********************************************************" << std::endl;
00131     ss << "* MoveGroup using: " << std::endl;
00132     for (std::size_t i = 0 ; i < capabilities_.size() ; ++i)
00133       ss << "*     - " << capabilities_[i]->getName() << std::endl;
00134     ss << "********************************************************" << std::endl;
00135     ROS_INFO_STREAM(ss.str());
00136   }
00137 
00138   ros::NodeHandle node_handle_;
00139   MoveGroupContextPtr context_;
00140   boost::shared_ptr<pluginlib::ClassLoader<MoveGroupCapability> > capability_plugin_loader_;
00141   std::vector<boost::shared_ptr<MoveGroupCapability> > capabilities_;
00142 };
00143 
00144 }
00145 
00146 int main(int argc, char **argv)
00147 {
00148   ros::init(argc, argv, move_group::NODE_NAME);
00149 
00150   ros::AsyncSpinner spinner(1);
00151   spinner.start();
00152 
00153   boost::shared_ptr<tf::TransformListener> tf(new tf::TransformListener(ros::Duration(10.0)));
00154 
00155   planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor(new planning_scene_monitor::PlanningSceneMonitor(ROBOT_DESCRIPTION, tf));
00156 
00157   if (planning_scene_monitor->getPlanningScene())
00158   {
00159     bool debug = false;
00160     for (int i = 1 ; i < argc ; ++i)
00161       if (strncmp(argv[i], "--debug", 7) == 0)
00162       {
00163         debug = true;
00164         break;
00165       }
00166     if (debug)
00167       ROS_INFO("MoveGroup debug mode is ON");
00168     else
00169       ROS_INFO("MoveGroup debug mode is OFF");
00170 
00171     move_group::MoveGroupExe mge(planning_scene_monitor, debug);
00172 
00173     planning_scene_monitor->startSceneMonitor();
00174     planning_scene_monitor->startWorldGeometryMonitor();
00175     planning_scene_monitor->startStateMonitor();
00176 
00177     planning_scene_monitor->publishDebugInformation(debug);
00178 
00179     mge.status();
00180 
00181     ros::waitForShutdown();
00182   }
00183   else
00184     ROS_ERROR("Planning scene not configured");
00185 
00186   return 0;
00187 }


move_group
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:32:44