joint_state.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_state/joint_state.h>
00038 
00039 robot_state::JointState::JointState(const robot_model::JointModel *jm) : joint_model_(jm)
00040 {
00041   joint_state_values_.resize(getVariableCount());
00042   variable_transform_.setIdentity();
00043   std::vector<double> values;
00044   joint_model_->getVariableDefaultValues(values);
00045   setVariableValues(values);
00046 
00047   horrible_velocity_placeholder_.resize(getVariableCount()); // not actually true; topology can be different
00048   horrible_acceleration_placeholder_.resize(getVariableCount()); // not actually true; topology can be different
00049 }
00050 
00051 robot_state::JointState::JointState(const JointState &other) :
00052   joint_model_(other.joint_model_), variable_transform_(other.variable_transform_), joint_state_values_(other.joint_state_values_), mimic_requests_(other.mimic_requests_)
00053 {
00054 }
00055 
00056 robot_state::JointState::~JointState()
00057 {
00058 }
00059 
00060 robot_state::JointState& robot_state::JointState::operator=(const robot_state::JointState &other)
00061 {
00062   if (this != &other)
00063   {
00064     assert(joint_state_values_.size() == other.joint_state_values_.size());
00065     joint_state_values_ = other.joint_state_values_;
00066     variable_transform_ = other.variable_transform_;
00067     mimic_requests_ = other.mimic_requests_;
00068   }
00069   return *this;
00070 }
00071 
00072 bool robot_state::JointState::setVariableValue(const std::string &variable, double value)
00073 {
00074   std::map<std::string, unsigned int>::const_iterator it = getVariableIndexMap().find(variable);
00075   if (it != getVariableIndexMap().end())
00076   {
00077     joint_state_values_[it->second] = value;
00078     joint_model_->updateTransform(joint_state_values_, variable_transform_);
00079     updateMimicJoints();
00080     return true;
00081   }
00082   else
00083   {
00084     logError("Cannot set variable %s to %lf for joint %s (variable not found).", variable.c_str(), value, getName().c_str());
00085     return false;
00086   }
00087 }
00088 
00089 bool robot_state::JointState::setVariableValues(const std::vector<double>& joint_state_values)
00090 {
00091   if (joint_state_values.size() != getVariableCount())
00092   {
00093     logError("Joint %s expects %u variables but values for %u variables were specified.",
00094              getName().c_str(), getVariableCount(), (unsigned int)joint_state_values.size());
00095     return false;
00096   }
00097   joint_state_values_ = joint_state_values;
00098   joint_model_->updateTransform(joint_state_values, variable_transform_);
00099   updateMimicJoints();
00100   return true;
00101 }
00102 
00103 void robot_state::JointState::setVariableValues(const double *joint_state_values)
00104 {
00105   std::copy(joint_state_values, joint_state_values + joint_state_values_.size(), joint_state_values_.begin());
00106   joint_model_->updateTransform(joint_state_values_, variable_transform_);
00107   updateMimicJoints();
00108 }
00109 
00110 void robot_state::JointState::setVariableValues(const std::map<std::string, double>& joint_value_map, std::vector<std::string>& missing)
00111 {
00112   bool has_any = false;
00113   const std::map<std::string, unsigned int> &vim = getVariableIndexMap();
00114   for (std::map<std::string, unsigned int>::const_iterator it = vim.begin(); it != vim.end(); ++it)
00115   {
00116     std::map<std::string, double>::const_iterator it2 = joint_value_map.find(it->first);
00117     if (it2 == joint_value_map.end())
00118       missing.push_back(it->first);
00119     else
00120     {
00121       has_any = true;
00122       joint_state_values_[it->second] = it2->second;
00123     }
00124   }
00125 
00126   if (has_any)
00127   {
00128     joint_model_->updateTransform(joint_state_values_, variable_transform_);
00129     updateMimicJoints();
00130   }
00131 }
00132 
00133 void robot_state::JointState::setVariableValues(const std::map<std::string, double>& joint_value_map)
00134 {
00135   bool update = false;
00136   const std::map<std::string, unsigned int> &vim = getVariableIndexMap();
00137   // iterate over the shorter list, for efficiency reasons
00138   if (joint_value_map.size() <= vim.size())
00139     for (std::map<std::string, double>::const_iterator it = joint_value_map.begin() ; it != joint_value_map.end() ; ++it)
00140     {
00141       std::map<std::string, unsigned int>::const_iterator it2 = vim.find(it->first);
00142       if (it2 != vim.end())
00143       {
00144         joint_state_values_[it2->second] = it->second;
00145         update = true;
00146       }
00147     }
00148   else
00149     for (std::map<std::string, unsigned int>::const_iterator it = vim.begin(); it != vim.end(); ++it)
00150     {
00151       std::map<std::string, double>::const_iterator it2 = joint_value_map.find(it->first);
00152       if (it2 != joint_value_map.end())
00153       {
00154         update = true;
00155         joint_state_values_[it->second] = it2->second;
00156       }
00157     }
00158   if (update)
00159   {
00160     joint_model_->updateTransform(joint_state_values_, variable_transform_);
00161     updateMimicJoints();
00162   }
00163 }
00164 
00165 void robot_state::JointState::setVariableValues(const Eigen::Affine3d& transform)
00166 {
00167   joint_model_->computeJointStateValues(transform, joint_state_values_);
00168   joint_model_->updateTransform(joint_state_values_, variable_transform_);
00169   updateMimicJoints();
00170 }
00171 
00172 void robot_state::JointState::updateMimicJoints()
00173 {
00174   for (std::size_t i = 0 ; i < mimic_requests_.size() ; ++i)
00175   {
00176     std::vector<double> mim_val(joint_state_values_.size());
00177     for (std::size_t j = 0 ; j < mim_val.size() ; ++j)
00178       mim_val[j] = joint_state_values_[j] * mimic_requests_[i]->getJointModel()->getMimicFactor() + mimic_requests_[i]->getJointModel()->getMimicOffset();
00179     mimic_requests_[i]->setVariableValues(&mim_val[0]);
00180   }
00181 }
00182 
00183 void robot_state::JointState::enforceBounds()
00184 {
00185   joint_model_->enforceBounds(joint_state_values_);
00186   joint_model_->updateTransform(joint_state_values_, variable_transform_);
00187   updateMimicJoints();
00188 }
00189 
00190 void robot_state::JointState::interpolate(const JointState *to, const double t, JointState *dest) const
00191 {
00192   joint_model_->interpolate(joint_state_values_, to->joint_state_values_, t, dest->joint_state_values_);
00193   dest->joint_model_->updateTransform(dest->joint_state_values_, dest->variable_transform_);
00194   dest->updateMimicJoints();
00195 }
00196 
00197 bool robot_state::JointState::allVariablesAreDefined(const std::map<std::string, double>& joint_value_map) const
00198 {
00199   const std::map<std::string, unsigned int> &vim = getVariableIndexMap();
00200   for (std::map<std::string, unsigned int>::const_iterator it = vim.begin() ; it != vim.end() ; ++it)
00201     if (joint_value_map.find(it->first) == joint_value_map.end())
00202       return false;
00203   return true;
00204 }


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