fix_workspace_bounds.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
39 #include <ros/ros.h>
40 
42 {
44 {
45 public:
46  static const std::string WBOUNDS_PARAM_NAME;
47 
49  {
50  if (!nh_.getParam(WBOUNDS_PARAM_NAME, workspace_extent_))
51  {
52  workspace_extent_ = 10.0;
53  ROS_INFO_STREAM("Param '" << WBOUNDS_PARAM_NAME << "' was not set. Using default value: " << workspace_extent_);
54  }
55  else
56  ROS_INFO_STREAM("Param '" << WBOUNDS_PARAM_NAME << "' was set to " << workspace_extent_);
57  workspace_extent_ /= 2.0;
58  }
59 
60  virtual std::string getDescription() const
61  {
62  return "Fix Workspace Bounds";
63  }
64 
65  virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
68  std::vector<std::size_t>& added_path_index) const
69  {
70  ROS_DEBUG("Running '%s'", getDescription().c_str());
71  const moveit_msgs::WorkspaceParameters& wparams = req.workspace_parameters;
72  if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
73  wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
74  wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
75  {
76  ROS_DEBUG("It looks like the planning volume was not specified. Using default values.");
78  moveit_msgs::WorkspaceParameters& default_wp = req2.workspace_parameters;
79  default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z = -workspace_extent_;
80  default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z = workspace_extent_;
81  return planner(planning_scene, req2, res);
82  }
83  else
84  return planner(planning_scene, req, res);
85  }
86 
87 private:
90 };
91 
92 const std::string FixWorkspaceBounds::WBOUNDS_PARAM_NAME = "default_workspace_bounds";
93 }
94 
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixWorkspaceBounds, planning_request_adapter::PlanningRequestAdapter)
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
moveit_msgs::MotionPlanRequest MotionPlanRequest
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
#define ROS_DEBUG(...)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:32