moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
38 #include <class_loader/class_loader.hpp>
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 #include <rclcpp/node.hpp>
42 #include <rclcpp/parameter_value.hpp>
43 
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.fix_workspace_bounds");
47 
49 {
50 public:
51  static const std::string WBOUNDS_PARAM_NAME;
52 
53  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
54  {
55  node_ = node;
56  workspace_extent_ = getParam(node_, LOGGER, parameter_namespace, WBOUNDS_PARAM_NAME, 10.0);
57  workspace_extent_ /= 2.0;
58  }
59 
60  std::string getDescription() const override
61  {
62  return "Fix Workspace Bounds";
63  }
64 
65  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
67  std::vector<std::size_t>& /*added_path_index*/) const override
68  {
69  RCLCPP_DEBUG(LOGGER, "Running '%s'", getDescription().c_str());
70  const moveit_msgs::msg::WorkspaceParameters& wparams = req.workspace_parameters;
71  if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
72  wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
73  wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
74  {
75  RCLCPP_DEBUG(LOGGER, "It looks like the planning volume was not specified. Using default values.");
77  moveit_msgs::msg::WorkspaceParameters& default_wp = req2.workspace_parameters;
78  default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z = -workspace_extent_;
79  default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z = workspace_extent_;
80  return planner(planning_scene, req2, res);
81  }
82  else
83  return planner(planning_scene, req, res);
84  }
85 
86 private:
87  rclcpp::Node::SharedPtr node_;
88  double workspace_extent_;
89 };
90 
91 const std::string FixWorkspaceBounds::WBOUNDS_PARAM_NAME = "default_workspace_bounds";
92 } // namespace default_planner_request_adapters
93 
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
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 > &) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string &parameter_namespace, const std::string &parameter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)