joint_state.h
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 Willow Garage, Inc. 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 #ifndef MOVEIT_ROBOT_STATE_JOINT_STATE_
00038 #define MOVEIT_ROBOT_STATE_JOINT_STATE_
00039 
00040 #include <moveit/robot_model/joint_model.h>
00041 
00042 namespace robot_state
00043 {
00044 
00045 class RobotState;
00046 
00048 class JointState
00049 {
00050   friend class RobotState;
00051 public:
00052   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00053 
00055   JointState(const robot_model::JointModel* jm);
00056 
00058   JointState(const JointState &other);
00059 
00061   ~JointState();
00062 
00064   JointState& operator=(const JointState &other);
00065 
00067   bool setVariableValue(const std::string &variable, double value);
00068 
00070   void setVariableValues(const std::map<std::string, double>& value_map);
00071 
00076   void setVariableValues(const std::map<std::string, double>& value_map, std::vector<std::string>& missing);
00077 
00079   bool setVariableValues(const std::vector<double>& value_vector);
00080 
00085   void setVariableValues(const double *value_vector);
00086 
00088   void setVariableValues(const Eigen::Affine3d& transform);
00089 
00091   void updateMimicJoints();
00092 
00095   bool allVariablesAreDefined(const std::map<std::string, double>& value_map) const;
00096 
00098   bool satisfiesBounds(double margin = 0.0) const
00099   {
00100     return joint_model_->satisfiesBounds(joint_state_values_, margin);
00101   }
00102 
00104   void enforceBounds();
00105 
00106   double distance(const JointState *other) const
00107   {
00108     return joint_model_->distance(joint_state_values_, other->joint_state_values_);
00109   }
00110 
00111   void interpolate(const JointState *to, const double t, JointState *dest) const;
00112 
00114   const std::string& getName() const
00115   {
00116     return joint_model_->getName();
00117   }
00118 
00120   robot_model::JointModel::JointType getType() const
00121   {
00122     return joint_model_->getType();
00123   }
00124 
00126   unsigned int getVariableCount() const
00127   {
00128     return joint_model_->getVariableCount();
00129   }
00130 
00132   const std::vector<double>& getVariableValues() const
00133   {
00134     return joint_state_values_;
00135   }
00136 
00138   std::vector<double>& getVariableValues()
00139   {
00140     return joint_state_values_;
00141   }
00142 
00144   const std::vector<std::string>& getVariableNames() const
00145   {
00146     return joint_model_->getVariableNames();
00147   }
00148 
00150   const std::vector<std::pair<double, double> > &getVariableBounds() const
00151   {
00152     return joint_model_->getVariableBounds();
00153   }
00154 
00156   const Eigen::Affine3d& getVariableTransform() const
00157   {
00158     return variable_transform_;
00159   }
00160 
00162   Eigen::Affine3d& getVariableTransform()
00163   {
00164     return variable_transform_;
00165   }
00166 
00168   const robot_model::JointModel* getJointModel() const
00169   {
00170     return joint_model_;
00171   }
00172 
00175   const std::map<std::string, unsigned int>& getVariableIndexMap() const
00176   {
00177     return joint_model_->getVariableIndexMap();
00178   }
00179 
00181   std::vector<double>& getVelocities()
00182   {
00183     return horrible_velocity_placeholder_;
00184   }
00185 
00187   std::vector<double>& getAccelerations()
00188   {
00189     return horrible_acceleration_placeholder_;
00190   }
00191 
00193   const std::vector<double>& getVelocities() const
00194   {
00195     return horrible_velocity_placeholder_;
00196   }
00197 
00199   const std::vector<double>& getAccelerations() const
00200   {
00201     return horrible_acceleration_placeholder_;
00202   }
00203 
00204 private:
00205 
00207   const robot_model::JointModel      *joint_model_;
00208 
00210   Eigen::Affine3d                     variable_transform_;
00211 
00213   std::vector<double>                 joint_state_values_;
00214 
00216   std::vector<double>                 horrible_velocity_placeholder_;
00217 
00219   std::vector<double>                 horrible_acceleration_placeholder_;
00220 
00222   std::vector<JointState*>            mimic_requests_;
00223 };
00224 
00225 }
00226 #endif


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