cartesian_robot.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 CARTESIAN_ROBOT_H_
00020 #define CARTESIAN_ROBOT_H_
00021 
00022 #include "descartes_core/robot_model.h"
00023 
00024 namespace descartes_trajectory_test
00025 {
00026 
00031 class CartesianRobot : public descartes_core::RobotModel
00032 {
00033 public:
00034 
00035   CartesianRobot();
00036 
00037   CartesianRobot(double pos_range, double orient_range, int dof = 6)  ;
00038 
00039   virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00040                      std::vector<double> &joint_pose) const;
00041 
00042   virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const;
00043 
00044   virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const;
00045 
00046   virtual bool isValid(const std::vector<double> &joint_pose) const;
00047 
00048   virtual bool isValid(const Eigen::Affine3d &pose) const;
00049 
00050   virtual int getDOF() const;
00051 
00052   virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00053                           const std::string& world_frame,const std::string& tcp_frame);
00054 
00055   virtual bool isValidMove(const std::vector<double>& from_joint_pose, const std::vector<double>& to_joint_pose,
00056                            double dt) const;
00057   
00058   double pos_range_;
00059   double orient_range_;
00060   int dof_;
00061 
00062 };
00063 
00064 
00065 }
00066 
00067 #endif // CARTESIAN_ROBOT_H


descartes_trajectory
Author(s): Jorge Nicho
autogenerated on Wed Aug 26 2015 11:21:27