fix_workspace_bounds.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_request_adapter/planning_request_adapter.h>
00038 #include <class_loader/class_loader.h>
00039 #include <ros/ros.h>
00040 
00041 namespace default_planner_request_adapters
00042 {
00043 
00044 class FixWorkspaceBounds : public planning_request_adapter::PlanningRequestAdapter
00045 {
00046 public:
00047 
00048   static const std::string WBOUNDS_PARAM_NAME;
00049 
00050   FixWorkspaceBounds() : planning_request_adapter::PlanningRequestAdapter(), nh_("~")
00051   {
00052     if (!nh_.getParam(WBOUNDS_PARAM_NAME, workspace_extent_))
00053     {
00054       workspace_extent_ = 10.0;
00055       ROS_INFO_STREAM("Param '" << WBOUNDS_PARAM_NAME << "' was not set. Using default value: " << workspace_extent_);
00056     }
00057     else
00058       ROS_INFO_STREAM("Param '" << WBOUNDS_PARAM_NAME << "' was set to " << workspace_extent_);
00059     workspace_extent_ /= 2.0;
00060   }
00061 
00062   virtual std::string getDescription() const { return "Fix Workspace Bounds"; }
00063 
00064   virtual bool adaptAndPlan(const PlannerFn &planner,
00065                             const planning_scene::PlanningSceneConstPtr& planning_scene,
00066                             const planning_interface::MotionPlanRequest &req,
00067                             planning_interface::MotionPlanResponse &res,
00068                             std::vector<std::size_t> &added_path_index) const
00069   {
00070     ROS_DEBUG("Running '%s'", getDescription().c_str());
00071     const moveit_msgs::WorkspaceParameters &wparams = req.workspace_parameters;
00072     if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
00073         wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
00074         wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
00075     {
00076       ROS_DEBUG("It looks like the planning volume was not specified. Using default values.");
00077       planning_interface::MotionPlanRequest req2 = req;
00078       moveit_msgs::WorkspaceParameters &default_wp = req2.workspace_parameters;
00079       default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z = -workspace_extent_;
00080       default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z = workspace_extent_;
00081       return planner(planning_scene, req2, res);
00082     }
00083     else
00084       return planner(planning_scene, req, res);
00085   }
00086 
00087 private:
00088   ros::NodeHandle nh_;
00089   double workspace_extent_;
00090 };
00091 
00092 const std::string FixWorkspaceBounds::WBOUNDS_PARAM_NAME = "default_workspace_bounds";
00093 
00094 }
00095 
00096 CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixWorkspaceBounds,
00097                             planning_request_adapter::PlanningRequestAdapter);


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:39