moveit_state_adapter.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Apache License)
00003  *
00004  * Copyright (c) 2014, Dan Solomon
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 MOVEIT_STATE_ADAPTER_H_
00020 #define MOVEIT_STATE_ADAPTER_H_
00021 
00022 #include "descartes_core/robot_model.h"
00023 #include "descartes_trajectory/cart_trajectory_pt.h"
00024 #include <moveit/planning_scene/planning_scene.h>
00025 #include <moveit/robot_model/robot_model.h>
00026 #include <moveit/robot_model_loader/robot_model_loader.h>
00027 #include <string>
00028 
00029 namespace descartes_moveit
00030 {
00034 class MoveitStateAdapter : public descartes_core::RobotModel
00035 {
00036 public:
00037   MoveitStateAdapter();
00038 
00039   virtual ~MoveitStateAdapter()
00040   {
00041   }
00042 
00043   virtual bool initialize(const std::string &robot_description, const std::string &group_name,
00044                           const std::string &world_frame, const std::string &tcp_frame);
00045 
00046   virtual bool initialize(robot_model::RobotModelConstPtr robot_model, const std::string &group_name,
00047                           const std::string &world_frame, const std::string &tcp_frame);
00048 
00049   virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00050                      std::vector<double> &joint_pose) const;
00051 
00052   virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const;
00053 
00054   virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const;
00055 
00056   virtual bool isValid(const std::vector<double> &joint_pose) const;
00057 
00058   virtual bool isValid(const Eigen::Affine3d &pose) const;
00059 
00060   virtual int getDOF() const;
00061 
00062   virtual bool isValidMove(const std::vector<double> &from_joint_pose, const std::vector<double> &to_joint_pose,
00063                            double dt) const;
00069   void setSeedStates(const std::vector<std::vector<double> > &seeds)
00070   {
00071     seed_states_ = seeds;
00072   }
00073 
00077   const std::vector<std::vector<double> > &getSeedStates() const
00078   {
00079     return seed_states_;
00080   }
00081 
00085   moveit::core::RobotStatePtr getState()
00086   {
00087     return robot_state_;
00088   }
00089 
00095   void setState(const moveit::core::RobotState &state);
00096 
00097 protected:
00104   bool getIK(const Eigen::Affine3d &pose, std::vector<double> &joint_pose) const;
00105 
00111   bool isInCollision(const std::vector<double> &joint_pose) const;
00112 
00117   std::vector<double> velocity_limits_;
00118 
00119   mutable moveit::core::RobotStatePtr robot_state_;
00120 
00121   planning_scene::PlanningScenePtr planning_scene_;
00122 
00123   robot_model::RobotModelConstPtr robot_model_ptr_;
00124 
00125   robot_model_loader::RobotModelLoaderPtr robot_model_loader_;
00126 
00127   const moveit::core::JointModelGroup *joint_group_;
00128 
00132   std::vector<std::vector<double> > seed_states_;
00133 
00137   std::string group_name_;
00138 
00142   std::string tool_frame_;
00143 
00147   std::string world_frame_;
00148 
00152   descartes_core::Frame world_to_root_;
00153 };
00154 
00155 }  // descartes_moveit
00156 
00157 #endif /* MOVEIT_STATE_ADAPTER_H_ */


descartes_moveit
Author(s): Shaun Edwards
autogenerated on Thu Jun 6 2019 21:36:08