moveit2
The MoveIt Motion Planning Framework for ROS 2.
check_start_state_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: The CheckStartStateBounds adapter validates if the start state is within the joint limits
37  * specified in the URDF. The need for this adapter arises in situations where the joint limits for the physical robot
38  * are not properly configured. The robot may then end up in a configuration where one or more of its joints is slightly
39  * outside its joint limits. In this case, the motion planner is unable to plan since it will think that the starting
40  * state is outside joint limits. The “CheckStartStateBounds” planning request adapter can “fix” the start state by
41  * moving it to the joint limit. However, this is obviously not the right solution every time - e.g. where the joint is
42  * really outside its joint limits by a large amount. A parameter for the adapter specifies how much the joint can be
43  * outside its limits for it to be “fixable”.
44  */
45 
49 #include <class_loader/class_loader.hpp>
50 #include <rclcpp/logger.hpp>
51 #include <rclcpp/logging.hpp>
52 #include <rclcpp/node.hpp>
53 #include <rclcpp/parameter_value.hpp>
54 #include <moveit/utils/logger.hpp>
55 
56 #include <default_request_adapter_parameters.hpp>
57 
59 {
60 
63 {
64 public:
65  CheckStartStateBounds() : logger_(moveit::getLogger("check_start_state_bounds"))
66  {
67  }
68 
69  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
70  {
71  param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);
72  }
73 
74  [[nodiscard]] std::string getDescription() const override
75  {
76  return std::string("CheckStartStateBounds");
77  }
78 
79  [[nodiscard]] moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
80  planning_interface::MotionPlanRequest& req) const override
81  {
82  RCLCPP_DEBUG(logger_, "Running '%s'", getDescription().c_str());
83 
84  // Get the specified start state
85  moveit::core::RobotState start_state = planning_scene->getCurrentState();
86  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
87 
88  // Get joint models
89  const std::vector<const moveit::core::JointModel*>& jmodels =
90  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
91  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
92  planning_scene->getRobotModel()->getJointModels();
93 
94  // Read parameters
95  const auto params = param_listener_->get_params();
96 
97  bool changed_req = false;
98  for (const moveit::core::JointModel* jmodel : jmodels)
99  {
100  // Check if we have a revolute, continuous joint. If we do, then we only need to make sure
101  // it is within the model's declared bounds (usually -Pi, Pi), since the values wrap around.
102  // It is possible that the encoder maintains values outside the range [-Pi, Pi], to inform
103  // how many times the joint was wrapped. Because of this, we remember the offsets for continuous
104  // joints, and we un-do them when the plan comes from the planner
105  switch (jmodel->getType())
106  {
108  {
109  if (static_cast<const moveit::core::RevoluteJointModel*>(jmodel)->isContinuous())
110  {
111  double initial = start_state.getJointPositions(jmodel)[0];
112  start_state.enforceBounds(jmodel);
113  double after = start_state.getJointPositions(jmodel)[0];
114  if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
115  {
116  changed_req = true;
117  }
118  }
119  break;
120  }
121  // Normalize yaw; no offset needs to be remembered
123  {
124  const double* p = start_state.getJointPositions(jmodel);
125  double copy[3] = { p[0], p[1], p[2] };
126  if (static_cast<const moveit::core::PlanarJointModel*>(jmodel)->normalizeRotation(copy))
127  {
128  start_state.setJointPositions(jmodel, copy);
129  changed_req = true;
130  }
131  break;
132  }
134  {
135  // Normalize quaternions
136  const double* p = start_state.getJointPositions(jmodel);
137  double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
138  if (static_cast<const moveit::core::FloatingJointModel*>(jmodel)->normalizeRotation(copy))
139  {
140  start_state.setJointPositions(jmodel, copy);
141  changed_req = true;
142  }
143  break;
144  }
145  default:
146  {
147  if (!start_state.satisfiesBounds(jmodel))
148  {
149  std::stringstream joint_values;
150  std::stringstream joint_bounds_low;
151  std::stringstream joint_bounds_hi;
152  const double* p = start_state.getJointPositions(jmodel);
153  for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
154  {
155  joint_values << p[k] << ' ';
156  }
157  const moveit::core::JointModel::Bounds& b = jmodel->getVariableBounds();
158  for (const moveit::core::VariableBounds& variable_bounds : b)
159  {
160  joint_bounds_low << variable_bounds.min_position_ << ' ';
161  joint_bounds_hi << variable_bounds.max_position_ << ' ';
162  }
163  RCLCPP_ERROR(logger_,
164  "Joint '%s' from the starting state is outside bounds by: [%s] should be in "
165  "the range [%s], [%s].",
166  jmodel->getName().c_str(), joint_values.str().c_str(), joint_bounds_low.str().c_str(),
167  joint_bounds_hi.str().c_str());
168  }
169  }
170  }
171  }
172 
173  // If we made any changes, consider using them them
174  if (params.fix_start_state && changed_req)
175  {
176  RCLCPP_WARN(logger_, "Changing start state.");
177  moveit::core::robotStateToRobotStateMsg(start_state, req.start_state);
178  return moveit::core::MoveItErrorCode(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, std::string(""),
179  getDescription());
180  }
181 
182  auto status = moveit::core::MoveItErrorCode();
183  if (!changed_req)
184  {
185  status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
186  }
187  else
188  {
189  status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
190  status.message = std::string("Start state out of bounds.");
191  }
192  status.source = getDescription();
193  return status;
194  }
195 
196 private:
197  std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
198  rclcpp::Logger logger_;
199 };
200 } // namespace default_planning_request_adapters
201 
The CheckStartStateBounds adapter validates if the start state is within the joint limits specified i...
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, 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 joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:543
bool satisfiesBounds(double margin=0.0) const
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
Main namespace for MoveIt.
Definition: exceptions.h:43
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)