fix_start_state_bounds.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/planning_request_adapter/planning_request_adapter.h>
00038 #include <boost/math/constants/constants.hpp>
00039 #include <moveit/trajectory_processing/trajectory_tools.h>
00040 #include <moveit/robot_state/conversions.h>
00041 #include <class_loader/class_loader.h>
00042 #include <ros/ros.h>
00043 
00044 namespace default_planner_request_adapters
00045 {
00046 
00047 class FixStartStateBounds : public planning_request_adapter::PlanningRequestAdapter
00048 {
00049 public:
00050 
00051   static const std::string BOUNDS_PARAM_NAME;
00052   static const std::string DT_PARAM_NAME;
00053 
00054   FixStartStateBounds() : planning_request_adapter::PlanningRequestAdapter(), nh_("~")
00055   {
00056     if (!nh_.getParam(BOUNDS_PARAM_NAME, bounds_dist_))
00057     {
00058       bounds_dist_ = 0.05;
00059       ROS_INFO_STREAM("Param '" << BOUNDS_PARAM_NAME << "' was not set. Using default value: " << bounds_dist_);
00060     }
00061     else
00062       ROS_INFO_STREAM("Param '" << BOUNDS_PARAM_NAME << "' was set to " << bounds_dist_);
00063 
00064     if (!nh_.getParam(DT_PARAM_NAME, max_dt_offset_))
00065     {
00066       max_dt_offset_ = 0.5;
00067       ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was not set. Using default value: " << max_dt_offset_);
00068     }
00069     else
00070       ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was set to " << max_dt_offset_);
00071   }
00072 
00073   virtual std::string getDescription() const { return "Fix Start State Bounds"; }
00074 
00075 
00076   virtual bool adaptAndPlan(const PlannerFn &planner,
00077                             const planning_scene::PlanningSceneConstPtr& planning_scene,
00078                             const planning_interface::MotionPlanRequest &req,
00079                             planning_interface::MotionPlanResponse &res,
00080                             std::vector<std::size_t> &added_path_index) const
00081   {
00082     ROS_DEBUG("Running '%s'", getDescription().c_str());
00083 
00084     // get the specified start state
00085     robot_state::RobotState start_state = planning_scene->getCurrentState();
00086     robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
00087 
00088     const std::vector<robot_state::JointState*> &jstates =
00089       planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
00090       start_state.getJointStateGroup(req.group_name)->getJointStateVector() :
00091       start_state.getJointStateVector();
00092 
00093     bool change_req = false;
00094     for (std::size_t i = 0 ; i < jstates.size() ; ++i)
00095     {
00096       // Check if we have a revolute, continuous joint. If we do, then we only need to make sure
00097       // it is within de model's declared bounds (usually -Pi, Pi), since the values wrap around.
00098       // It is possible that the encoder maintains values outside the range [-Pi, Pi], to inform
00099       // how many times the joint was wrapped. Because of this, we remember the offsets for continuous
00100       // joints, and we un-do them when the plan comes from the planner
00101 
00102       const robot_model::JointModel* jm = jstates[i]->getJointModel();
00103       if (jm->getType() == robot_model::JointModel::REVOLUTE)
00104       {
00105         if (static_cast<const robot_model::RevoluteJointModel*>(jm)->isContinuous())
00106         {
00107           double initial = jstates[i]->getVariableValues()[0];
00108           jstates[i]->enforceBounds();
00109           double after = jstates[i]->getVariableValues()[0];
00110           if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
00111             change_req = true;
00112         }
00113       }
00114       else
00115         // Normalize yaw; no offset needs to be remembered
00116         if (jm->getType() == robot_model::JointModel::PLANAR)
00117         {
00118           double initial = jstates[i]->getVariableValues()[2];
00119           if (static_cast<const robot_model::PlanarJointModel*>(jm)->normalizeRotation(jstates[i]->getVariableValues()))
00120             change_req = true;
00121         }
00122         else
00123           // Normalize quaternions
00124           if (jm->getType() == robot_model::JointModel::FLOATING)
00125           {
00126             if (static_cast<const robot_model::FloatingJointModel*>(jm)->normalizeRotation(jstates[i]->getVariableValues()))
00127               change_req = true;
00128           }
00129     }
00130 
00131     // pointer to a prefix state we could possibly add, if we detect we have to make changes
00132     robot_state::RobotStatePtr prefix_state;
00133     for (std::size_t i = 0 ; i < jstates.size() ; ++i)
00134     {
00135       if (!jstates[i]->satisfiesBounds())
00136       {
00137         if (jstates[i]->satisfiesBounds(bounds_dist_))
00138         {
00139           if (!prefix_state)
00140             prefix_state.reset(new robot_state::RobotState(start_state));
00141           jstates[i]->enforceBounds();
00142           change_req = true;
00143           ROS_INFO("Starting state is just outside bounds (joint '%s'). Assuming within bounds.", jstates[i]->getName().c_str());
00144         }
00145         else
00146         {
00147           std::stringstream joint_values;
00148           std::stringstream joint_bounds_low;
00149           std::stringstream joint_bounds_hi;
00150           for (std::size_t k = 0 ; k < jstates[i]->getVariableValues().size() ; ++k)
00151             joint_values << jstates[i]->getVariableValues()[k] << " ";
00152           for (std::size_t k = 0 ; k < jstates[i]->getVariableBounds().size() ; ++k)
00153           {
00154             joint_bounds_low << jstates[i]->getVariableBounds()[k].first << " ";
00155             joint_bounds_hi << jstates[i]->getVariableBounds()[k].second << " ";
00156           }
00157           ROS_WARN_STREAM("Joint '" << jstates[i]->getName() << "' from the starting state is outside bounds by a significant margin: [ " << joint_values.str() << "] should be in the range [ " << joint_bounds_low.str() <<
00158                           "], [ " << joint_bounds_hi.str() << "] but the error above the ~" << BOUNDS_PARAM_NAME << " parameter (currently set to " << bounds_dist_ << ")");
00159         }
00160       }
00161     }
00162 
00163     bool solved;
00164     // if we made any changes, use them
00165     if (change_req)
00166     {
00167       planning_interface::MotionPlanRequest req2 = req;
00168       robot_state::robotStateToRobotStateMsg(start_state, req2.start_state, false);
00169       solved = planner(planning_scene, req2, res);
00170     }
00171     else
00172       solved = planner(planning_scene, req, res);
00173 
00174     // re-add the prefix state, if it was constructed
00175     if (prefix_state && res.trajectory_ && !res.trajectory_->empty())
00176     {
00177       // heuristically decide a duration offset for the trajectory (induced by the additional point added as a prefix to the computed trajectory)
00178       res.trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_, res.trajectory_->getAverageSegmentDuration()));
00179       res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
00180       added_path_index.push_back(0);
00181     }
00182 
00183     return solved;
00184   }
00185 
00186 private:
00187 
00188   ros::NodeHandle nh_;
00189   double bounds_dist_;
00190   double max_dt_offset_;
00191 };
00192 
00193 
00194 const std::string FixStartStateBounds::BOUNDS_PARAM_NAME = "start_state_max_bounds_error";
00195 const std::string FixStartStateBounds::DT_PARAM_NAME = "start_state_max_dt";
00196 
00197 }
00198 
00199 CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateBounds,
00200                             planning_request_adapter::PlanningRequestAdapter);


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:39