moveit2
The MoveIt Motion Planning Framework for ROS 2.
fix_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 
38 #include <boost/math/constants/constants.hpp>
41 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 #include <rclcpp/parameter_value.hpp>
46 
48 {
49 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.fix_start_state_bounds");
50 
52 {
53 public:
54  static const std::string BOUNDS_PARAM_NAME;
55  static const std::string DT_PARAM_NAME;
56 
57  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
58  {
59  node_ = node;
60  bounds_dist_ = getParam(node_, LOGGER, parameter_namespace, BOUNDS_PARAM_NAME, 0.05);
61  max_dt_offset_ = getParam(node_, LOGGER, parameter_namespace, DT_PARAM_NAME, 0.5);
62  }
63 
64  std::string getDescription() const override
65  {
66  return "Fix Start State Bounds";
67  }
68 
69  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
71  std::vector<std::size_t>& added_path_index) const override
72  {
73  RCLCPP_DEBUG(LOGGER, "Running '%s'", getDescription().c_str());
74 
75  // get the specified start state
76  moveit::core::RobotState start_state = planning_scene->getCurrentState();
77  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
78 
79  const std::vector<const moveit::core::JointModel*>& jmodels =
80  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
81  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
82  planning_scene->getRobotModel()->getJointModels();
83 
84  bool change_req = false;
85  for (const moveit::core::JointModel* jm : jmodels)
86  {
87  // Check if we have a revolute, continuous joint. If we do, then we only need to make sure
88  // it is within de model's declared bounds (usually -Pi, Pi), since the values wrap around.
89  // It is possible that the encoder maintains values outside the range [-Pi, Pi], to inform
90  // how many times the joint was wrapped. Because of this, we remember the offsets for continuous
91  // joints, and we un-do them when the plan comes from the planner
92 
93  if (jm->getType() == moveit::core::JointModel::REVOLUTE)
94  {
95  if (static_cast<const moveit::core::RevoluteJointModel*>(jm)->isContinuous())
96  {
97  double initial = start_state.getJointPositions(jm)[0];
98  start_state.enforceBounds(jm);
99  double after = start_state.getJointPositions(jm)[0];
100  if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
101  change_req = true;
102  }
103  }
104  else
105  // Normalize yaw; no offset needs to be remembered
106  if (jm->getType() == moveit::core::JointModel::PLANAR)
107  {
108  const double* p = start_state.getJointPositions(jm);
109  double copy[3] = { p[0], p[1], p[2] };
110  if (static_cast<const moveit::core::PlanarJointModel*>(jm)->normalizeRotation(copy))
111  {
112  start_state.setJointPositions(jm, copy);
113  change_req = true;
114  }
115  }
116  else
117  // Normalize quaternions
118  if (jm->getType() == moveit::core::JointModel::FLOATING)
119  {
120  const double* p = start_state.getJointPositions(jm);
121  double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
122  if (static_cast<const moveit::core::FloatingJointModel*>(jm)->normalizeRotation(copy))
123  {
124  start_state.setJointPositions(jm, copy);
125  change_req = true;
126  }
127  }
128  }
129 
130  // pointer to a prefix state we could possibly add, if we detect we have to make changes
131  moveit::core::RobotStatePtr prefix_state;
132  for (const moveit::core::JointModel* jmodel : jmodels)
133  {
134  if (!start_state.satisfiesBounds(jmodel))
135  {
136  if (start_state.satisfiesBounds(jmodel, bounds_dist_))
137  {
138  if (!prefix_state)
139  prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
140  start_state.enforceBounds(jmodel);
141  change_req = true;
142  RCLCPP_INFO(LOGGER, "Starting state is just outside bounds (joint '%s'). Assuming within bounds.",
143  jmodel->getName().c_str());
144  }
145  else
146  {
147  std::stringstream joint_values;
148  std::stringstream joint_bounds_low;
149  std::stringstream joint_bounds_hi;
150  const double* p = start_state.getJointPositions(jmodel);
151  for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
152  joint_values << p[k] << " ";
153  const moveit::core::JointModel::Bounds& b = jmodel->getVariableBounds();
154  for (const moveit::core::VariableBounds& variable_bounds : b)
155  {
156  joint_bounds_low << variable_bounds.min_position_ << " ";
157  joint_bounds_hi << variable_bounds.max_position_ << " ";
158  }
159  RCLCPP_WARN(LOGGER,
160  "Joint '%s' from the starting state is outside bounds by a significant margin: [%s] should be in "
161  "the range [%s], [%s] but the error above the ~%s parameter (currently set to %f)",
162  jmodel->getName().c_str(), joint_values.str().c_str(), joint_bounds_low.str().c_str(),
163  joint_bounds_hi.str().c_str(), BOUNDS_PARAM_NAME.c_str(), bounds_dist_);
164  }
165  }
166  }
167 
168  bool solved;
169  // if we made any changes, use them
170  if (change_req)
171  {
173  moveit::core::robotStateToRobotStateMsg(start_state, req2.start_state);
174  solved = planner(planning_scene, req2, res);
175  }
176  else
177  solved = planner(planning_scene, req, res);
178 
179  // re-add the prefix state, if it was constructed
180  if (prefix_state && res.trajectory_ && !res.trajectory_->empty())
181  {
182  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a prefix to
183  // the computed trajectory)
184  res.trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_,
185  res.trajectory_->getAverageSegmentDuration()));
186  res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
187  // we add a prefix point, so we need to bump any previously added index positions
188  for (std::size_t& added_index : added_path_index)
189  added_index++;
190  added_path_index.push_back(0);
191  }
192 
193  return solved;
194  }
195 
196 private:
197  rclcpp::Node::SharedPtr node_;
198  double bounds_dist_;
199  double max_dt_offset_;
200 };
201 
202 const std::string FixStartStateBounds::BOUNDS_PARAM_NAME = "start_state_max_bounds_error";
203 const std::string FixStartStateBounds::DT_PARAM_NAME = "start_state_max_dt";
204 } // namespace default_planner_request_adapters
205 
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
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,...
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 override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
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
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:557
bool satisfiesBounds(double margin=0.0) const
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
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
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.
p
Definition: pick.py:62
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)