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_PRISMATIC_JOINT_MODEL_
00038 #define MOVEIT_CORE_ROBOT_MODEL_PRISMATIC_JOINT_MODEL_
00039
00040 #include <moveit/robot_model/joint_model.h>
00041
00042 namespace moveit
00043 {
00044 namespace core
00045 {
00047 class PrismaticJointModel : public JointModel
00048 {
00049 public:
00050 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00051
00052 PrismaticJointModel(const std::string& name);
00053
00054 virtual void getVariableDefaultPositions(double* values, const Bounds& other_bounds) const;
00055 virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
00056 const Bounds& other_bounds) const;
00057 virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
00058 const Bounds& other_bounds, const double* near,
00059 const double distance) const;
00060 virtual bool enforcePositionBounds(double* values, const Bounds& other_bounds) const;
00061 virtual bool satisfiesPositionBounds(const double* values, const Bounds& other_bounds, double margin) const;
00062
00063 virtual void interpolate(const double* from, const double* to, const double t, double* state) const;
00064 virtual unsigned int getStateSpaceDimension() const;
00065 virtual double getMaximumExtent(const Bounds& other_bounds) const;
00066 virtual double distance(const double* values1, const double* values2) const;
00067
00068 virtual void computeTransform(const double* joint_values, Eigen::Affine3d& transf) const;
00069 virtual void computeVariablePositions(const Eigen::Affine3d& transf, double* joint_values) const;
00070
00072 const Eigen::Vector3d& getAxis() const
00073 {
00074 return axis_;
00075 }
00076
00078 void setAxis(const Eigen::Vector3d& axis)
00079 {
00080 axis_ = axis;
00081 }
00082
00083 protected:
00085 Eigen::Vector3d axis_;
00086 };
00087 }
00088 }
00089
00090 #endif