Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_CORE_ROBOT_MODEL_REVOLUTE_JOINT_MODEL_
00038 #define MOVEIT_CORE_ROBOT_MODEL_REVOLUTE_JOINT_MODEL_
00039
00040 #include <moveit/robot_model/joint_model.h>
00041
00042 namespace moveit
00043 {
00044 namespace core
00045 {
00046
00048 class RevoluteJointModel : public JointModel
00049 {
00050 public:
00051 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00052
00053 RevoluteJointModel(const std::string& name);
00054 virtual void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const;
00055 virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const;
00056 virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds,
00057 const double *near, const double distance) const;
00058 virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const;
00059 virtual bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const;
00060
00061 virtual void interpolate(const double *from, const double *to, const double t, double *state) const;
00062 virtual unsigned int getStateSpaceDimension() const;
00063 virtual double getMaximumExtent(const Bounds &other_bounds) const;
00064 virtual double distance(const double *values1, const double *values2) const;
00065
00066 virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const;
00067 virtual void computeVariablePositions(const Eigen::Affine3d& transf, double *joint_values) const;
00068
00069 void setContinuous(bool flag);
00070
00072 bool isContinuous() const
00073 {
00074 return continuous_;
00075 }
00076
00078 const Eigen::Vector3d& getAxis() const
00079 {
00080 return axis_;
00081 }
00082
00084 void setAxis(const Eigen::Vector3d &axis);
00085
00086 protected:
00087
00089 Eigen::Vector3d axis_;
00090
00092 bool continuous_;
00093
00094 private:
00095
00096 double x2_, y2_, z2_, xy_, xz_, yz_;
00097
00098 };
00099
00100 }
00101 }
00102
00103 #endif