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>
42 #include <ros/ros.h>
43 
45 {
47 {
48 public:
49  static const std::string BOUNDS_PARAM_NAME;
50  static const std::string DT_PARAM_NAME;
51 
53  {
54  if (!nh_.getParam(BOUNDS_PARAM_NAME, bounds_dist_))
55  {
56  bounds_dist_ = 0.05;
57  ROS_INFO_STREAM("Param '" << BOUNDS_PARAM_NAME << "' was not set. Using default value: " << bounds_dist_);
58  }
59  else
60  ROS_INFO_STREAM("Param '" << BOUNDS_PARAM_NAME << "' was set to " << bounds_dist_);
61 
62  if (!nh_.getParam(DT_PARAM_NAME, max_dt_offset_))
63  {
64  max_dt_offset_ = 0.5;
65  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was not set. Using default value: " << max_dt_offset_);
66  }
67  else
68  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was set to " << max_dt_offset_);
69  }
70 
71  virtual std::string getDescription() const
72  {
73  return "Fix Start State Bounds";
74  }
75 
76  virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
79  std::vector<std::size_t>& added_path_index) const
80  {
81  ROS_DEBUG("Running '%s'", getDescription().c_str());
82 
83  // get the specified start state
84  robot_state::RobotState start_state = planning_scene->getCurrentState();
85  robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
86 
87  const std::vector<const robot_model::JointModel*>& jmodels =
88  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
89  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
90  planning_scene->getRobotModel()->getJointModels();
91 
92  bool change_req = false;
93  for (std::size_t i = 0; i < jmodels.size(); ++i)
94  {
95  // Check if we have a revolute, continuous joint. If we do, then we only need to make sure
96  // it is within de model's declared bounds (usually -Pi, Pi), since the values wrap around.
97  // It is possible that the encoder maintains values outside the range [-Pi, Pi], to inform
98  // how many times the joint was wrapped. Because of this, we remember the offsets for continuous
99  // joints, and we un-do them when the plan comes from the planner
100 
101  const robot_model::JointModel* jm = jmodels[i];
102  if (jm->getType() == robot_model::JointModel::REVOLUTE)
103  {
104  if (static_cast<const robot_model::RevoluteJointModel*>(jm)->isContinuous())
105  {
106  double initial = start_state.getJointPositions(jm)[0];
107  start_state.enforceBounds(jm);
108  double after = start_state.getJointPositions(jm)[0];
109  if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
110  change_req = true;
111  }
112  }
113  else
114  // Normalize yaw; no offset needs to be remembered
115  if (jm->getType() == robot_model::JointModel::PLANAR)
116  {
117  const double* p = start_state.getJointPositions(jm);
118  double copy[3] = { p[0], p[1], p[2] };
119  if (static_cast<const robot_model::PlanarJointModel*>(jm)->normalizeRotation(copy))
120  {
121  start_state.setJointPositions(jm, copy);
122  change_req = true;
123  }
124  }
125  else
126  // Normalize quaternions
127  if (jm->getType() == robot_model::JointModel::FLOATING)
128  {
129  const double* p = start_state.getJointPositions(jm);
130  double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
131  if (static_cast<const robot_model::FloatingJointModel*>(jm)->normalizeRotation(copy))
132  {
133  start_state.setJointPositions(jm, copy);
134  change_req = true;
135  }
136  }
137  }
138 
139  // pointer to a prefix state we could possibly add, if we detect we have to make changes
140  robot_state::RobotStatePtr prefix_state;
141  for (std::size_t i = 0; i < jmodels.size(); ++i)
142  {
143  if (!start_state.satisfiesBounds(jmodels[i]))
144  {
145  if (start_state.satisfiesBounds(jmodels[i], bounds_dist_))
146  {
147  if (!prefix_state)
148  prefix_state.reset(new robot_state::RobotState(start_state));
149  start_state.enforceBounds(jmodels[i]);
150  change_req = true;
151  ROS_INFO("Starting state is just outside bounds (joint '%s'). Assuming within bounds.",
152  jmodels[i]->getName().c_str());
153  }
154  else
155  {
156  std::stringstream joint_values;
157  std::stringstream joint_bounds_low;
158  std::stringstream joint_bounds_hi;
159  const double* p = start_state.getJointPositions(jmodels[i]);
160  for (std::size_t k = 0; k < jmodels[i]->getVariableCount(); ++k)
161  joint_values << p[k] << " ";
162  const robot_model::JointModel::Bounds& b = jmodels[i]->getVariableBounds();
163  for (std::size_t k = 0; k < b.size(); ++k)
164  {
165  joint_bounds_low << b[k].min_position_ << " ";
166  joint_bounds_hi << b[k].max_position_ << " ";
167  }
168  ROS_WARN_STREAM("Joint '" << jmodels[i]->getName()
169  << "' from the starting state is outside bounds by a significant margin: [ "
170  << joint_values.str() << "] should be in the range [ " << joint_bounds_low.str()
171  << "], [ " << joint_bounds_hi.str() << "] but the error above the ~"
172  << BOUNDS_PARAM_NAME << " parameter (currently set to " << bounds_dist_ << ")");
173  }
174  }
175  }
176 
177  bool solved;
178  // if we made any changes, use them
179  if (change_req)
180  {
182  robot_state::robotStateToRobotStateMsg(start_state, req2.start_state, false);
183  solved = planner(planning_scene, req2, res);
184  }
185  else
186  solved = planner(planning_scene, req, res);
187 
188  // re-add the prefix state, if it was constructed
189  if (prefix_state && res.trajectory_ && !res.trajectory_->empty())
190  {
191  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a prefix to
192  // the computed trajectory)
193  res.trajectory_->setWayPointDurationFromPrevious(
194  0, std::min(max_dt_offset_, res.trajectory_->getAverageSegmentDuration()));
195  res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
196  // we add a prefix point, so we need to bump any previously added index positions
197  for (std::size_t i = 0; i < added_path_index.size(); ++i)
198  added_path_index[i]++;
199  added_path_index.push_back(0);
200  }
201 
202  return solved;
203  }
204 
205 private:
207  double bounds_dist_;
209 };
210 
211 const std::string FixStartStateBounds::BOUNDS_PARAM_NAME = "start_state_max_bounds_error";
212 const std::string FixStartStateBounds::DT_PARAM_NAME = "start_state_max_dt";
213 }
214 
robot_trajectory::RobotTrajectoryPtr trajectory_
std::string getName(void *handle)
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateBounds, 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
#define ROS_INFO(...)
#define ROS_WARN_STREAM(args)
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 Sun Oct 18 2020 13:17:33