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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03