moveit2
The MoveIt Motion Planning Framework for ROS 2.
validate_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  * Desc: If not specified by the planning request, this request adapter will specify a default workspace for planning.
37  * The default workspace is a cube whose edge length is defined with a ROS 2 parameter.
38  */
39 
41 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 #include <moveit/utils/logger.hpp>
46 
47 #include <default_request_adapter_parameters.hpp>
48 
50 {
51 
54 {
55 public:
56  ValidateWorkspaceBounds() : logger_(moveit::getLogger("moveit.ros.validate_workspace_bounds"))
57  {
58  }
59 
60  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
61  {
62  param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);
63  }
64 
65  [[nodiscard]] std::string getDescription() const override
66  {
67  return std::string("ValidateWorkspaceBounds");
68  }
69 
70  [[nodiscard]] moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr& /*planning_scene*/,
71  planning_interface::MotionPlanRequest& req) const override
72  {
73  RCLCPP_DEBUG(logger_, "Running '%s'", getDescription().c_str());
74  const moveit_msgs::msg::WorkspaceParameters& wparams = req.workspace_parameters;
75  if (std::abs(wparams.min_corner.x) < std::numeric_limits<double>::epsilon() &&
76  std::abs(wparams.min_corner.y) < std::numeric_limits<double>::epsilon() &&
77  std::abs(wparams.min_corner.z) < std::numeric_limits<double>::epsilon() &&
78  std::abs(wparams.max_corner.x) < std::numeric_limits<double>::epsilon() &&
79  std::abs(wparams.max_corner.y) < std::numeric_limits<double>::epsilon() &&
80  std::abs(wparams.max_corner.z) < std::numeric_limits<double>::epsilon())
81  {
82  RCLCPP_WARN(logger_, "It looks like the planning volume was not specified. Using default values.");
83  moveit_msgs::msg::WorkspaceParameters& default_wp = req.workspace_parameters;
84  const auto params = param_listener_->get_params();
85 
86  default_wp.min_corner.x = default_wp.min_corner.y = default_wp.min_corner.z =
87  -params.default_workspace_bounds / 2.0;
88  default_wp.max_corner.x = default_wp.max_corner.y = default_wp.max_corner.z =
89  params.default_workspace_bounds / 2.0;
90  }
91  return moveit::core::MoveItErrorCode(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, std::string(""), getDescription());
92  }
93 
94 private:
95  std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
96  rclcpp::Logger logger_;
97 };
98 } // namespace default_planning_request_adapters
99 
If not specified by the planning request, this request adapter will specify a default workspace for p...
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::string getDescription() const override
Get a description of this adapter.
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
Main namespace for MoveIt.
Definition: exceptions.hpp:43
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)