revolute_joint_model.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_MODEL_REVOLUTE_JOINT_MODEL_
00038 #define MOVEIT_ROBOT_MODEL_REVOLUTE_JOINT_MODEL_
00039 
00040 #include <moveit/robot_model/joint_model.h>
00041 
00042 namespace robot_model
00043 {
00044 
00046 class RevoluteJointModel : public JointModel
00047 {
00048   friend class RobotModel;
00049 public:
00050   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00051 
00052   RevoluteJointModel(const std::string& name);
00053   virtual void getVariableDefaultValues(std::vector<double> &values, const Bounds &other_bounds) const;
00054   virtual void getVariableRandomValues(random_numbers::RandomNumberGenerator &rng, std::vector<double> &values, const Bounds &other_bounds) const;
00055   virtual void getVariableRandomValuesNearBy(random_numbers::RandomNumberGenerator &rng, std::vector<double> &values, const Bounds &other_bounds,
00056                                              const std::vector<double> &near, const double distance) const;
00057   virtual void enforceBounds(std::vector<double> &values, const Bounds &other_bounds) const;
00058   virtual bool satisfiesBounds(const std::vector<double> &values, const Bounds &other_bounds, double margin) const;
00059 
00060   virtual void interpolate(const std::vector<double> &from, const std::vector<double> &to, const double t, std::vector<double> &state) const;
00061   virtual unsigned int getStateSpaceDimension() const;
00062   virtual double getMaximumExtent(const Bounds &other_bounds) const;
00063   virtual double distance(const std::vector<double> &values1, const std::vector<double> &values2) const;
00064   virtual void computeDefaultVariableLimits();
00065 
00066   virtual void computeTransform(const std::vector<double>& joint_values, Eigen::Affine3d &transf) const;
00067   virtual void computeJointStateValues(const Eigen::Affine3d& transf, std::vector<double> &joint_values) const;
00068   virtual void updateTransform(const std::vector<double>& joint_values, Eigen::Affine3d &transf) const;
00069 
00071   bool isContinuous() const
00072   {
00073     return continuous_;
00074   }
00075 
00077   const Eigen::Vector3d& getAxis() const
00078   {
00079     return axis_;
00080   }
00081 
00082 protected:
00084   Eigen::Vector3d axis_;
00085 
00087   bool continuous_;
00088 };
00089 
00090 }
00091 
00092 #endif


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