joint_model.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, 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, E. Gil Jones */
00036 
00037 #include <moveit/robot_model/joint_model.h>
00038 #include <moveit/robot_model/link_model.h>
00039 
00040 robot_model::JointModel::JointModel(const std::string& name) :
00041   name_(name), type_(UNKNOWN), max_velocity_(0.0), parent_link_model_(NULL), child_link_model_(NULL),
00042   mimic_(NULL), mimic_factor_(1.0), mimic_offset_(0.0), passive_(false), distance_factor_(1.0), tree_index_(-1)
00043 {
00044 }
00045 
00046 robot_model::JointModel::~JointModel()
00047 {
00048 }
00049 
00050 bool robot_model::JointModel::getVariableBounds(const std::string& variable, std::pair<double, double>& bounds) const
00051 {
00052   std::map<std::string, unsigned int>::const_iterator it = variable_index_.find(variable);
00053   if (it == variable_index_.end())
00054   {
00055     logWarn("Could not find variable '%s' to get bounds for within joint '%s'", variable.c_str(), name_.c_str());
00056     return false;
00057   }
00058   bounds = variable_bounds_[it->second];
00059   return true;
00060 }
00061 
00062 bool robot_model::JointModel::setVariableBounds(const std::string& variable, const std::pair<double, double>& bounds)
00063 {
00064   std::map<std::string, unsigned int>::const_iterator it = variable_index_.find(variable);
00065   if (it == variable_index_.end())
00066   {
00067     logWarn("Could not find variable '%s' to set bounds for within joint '%s'", variable.c_str(), name_.c_str());
00068     return false;
00069   }
00070   variable_bounds_[it->second] = bounds;
00071   return true;
00072 }
00073 
00074 void robot_model::JointModel::getVariableDefaultValues(std::map<std::string, double> &values, const Bounds &bounds) const
00075 {
00076   std::vector<double> defv;
00077   defv.reserve(variable_names_.size());
00078   getVariableDefaultValues(defv, bounds);
00079   for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00080     values[variable_names_[i]] = defv[i];
00081 }
00082 
00083 void robot_model::JointModel::getVariableRandomValues(random_numbers::RandomNumberGenerator &rng, std::map<std::string, double> &values, const Bounds &bounds) const
00084 {
00085   std::vector<double> rv;
00086   rv.reserve(variable_names_.size());
00087   getVariableRandomValues(rng, rv, bounds);
00088   for (std::size_t i = 0 ; i < variable_names_.size() ; ++i)
00089     values[variable_names_[i]] = rv[i];
00090 }
00091 
00092 void robot_model::JointModel::computeDefaultVariableLimits()
00093 {
00094   default_limits_.clear();
00095   for (std::size_t i = 0; i < variable_names_.size(); ++i)
00096   {
00097     moveit_msgs::JointLimits lim;
00098     lim.joint_name = variable_names_[i];
00099     lim.has_position_limits = true;
00100     lim.min_position = variable_bounds_[i].first;
00101     lim.max_position = variable_bounds_[i].second;
00102     if (max_velocity_ != 0.0)
00103       lim.has_velocity_limits = true;
00104     else
00105       lim.has_velocity_limits = false;
00106     lim.max_velocity = max_velocity_;
00107     lim.has_acceleration_limits = false;
00108     lim.max_acceleration = 0.0;
00109     default_limits_.push_back(lim);
00110   }
00111 }
00112 
00113 void robot_model::JointModel::setVariableLimits(const std::vector<moveit_msgs::JointLimits>& jlim)
00114 {
00115   user_specified_limits_.clear();
00116   for (std::size_t j = 0; j < variable_names_.size(); ++j)
00117     for (std::size_t i = 0 ; i < jlim.size() ; ++i)
00118       if (jlim[i].joint_name == variable_names_[j])
00119       {
00120         user_specified_limits_.push_back(jlim[i]);
00121         break;
00122       }
00123   if (user_specified_limits_.size() > 0 && user_specified_limits_.size() != variable_names_.size())
00124   {
00125     logError("Incorrect number of joint limits was specified!");
00126     user_specified_limits_.clear();
00127   }
00128 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:46