robot_model.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Southwest Research Institute
00005  *
00006  * Licensed under the Apache License, Version 2.0 (the "License");
00007  * you may not use this file except in compliance with the License.
00008  * You may obtain a copy of the License at
00009  *
00010  * http://www.apache.org/licenses/LICENSE-2.0
00011  *
00012  * Unless required by applicable law or agreed to in writing, software
00013  * distributed under the License is distributed on an "AS IS" BASIS,
00014  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015  * See the License for the specific language governing permissions and
00016  * limitations under the License.
00017  */
00018 
00019 #ifndef ROBOT_KINEMATICS_H_
00020 #define ROBOT_KINEMATICS_H_
00021 
00022 // TODO: The include below picks up Eigen::Affine3d, but there is probably a better way
00023 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00024 #include "descartes_core/utils.h"
00025 
00026 namespace descartes_core
00027 {
00028 DESCARTES_CLASS_FORWARD(RobotModel);
00029 
00039 class RobotModel
00040 {
00041 public:
00042   virtual ~RobotModel()
00043   {
00044   }
00045 
00053   virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00054                      std::vector<double> &joint_pose) const = 0;
00055 
00064   virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const = 0;
00065 
00072   virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const = 0;
00073 
00078   virtual int getDOF() const = 0;
00079 
00085   virtual bool isValid(const std::vector<double> &joint_pose) const = 0;
00086 
00092   virtual bool isValid(const Eigen::Affine3d &pose) const = 0;
00093 
00102   virtual bool initialize(const std::string &robot_description, const std::string &group_name,
00103                           const std::string &world_frame, const std::string &tcp_frame) = 0;
00104 
00109   virtual void setCheckCollisions(bool check_collisions)
00110   {
00111     check_collisions_ = check_collisions;
00112   }
00113 
00118   virtual bool getCheckCollisions()
00119   {
00120     return check_collisions_;
00121   }
00122 
00131   virtual bool isValidMove(const std::vector<double> &from_joint_pose, const std::vector<double> &to_joint_pose,
00132                            double dt) const = 0;
00133 
00134 protected:
00135   RobotModel() : check_collisions_(false)
00136   {
00137   }
00138 
00139   bool check_collisions_;
00140 };
00141 
00142 }  // descartes_core
00143 
00144 #endif /* ROBOT_KINEMATICS_H_ */


descartes_core
Author(s): Dan Solomon
autogenerated on Thu Jun 6 2019 21:35:59