ompl_ros_rpy_ik_state_transformer.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Willow Garage, Inc. nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00037 #ifndef OMPL_ROS_RPY_IK_STATE_TRANSFORMER_H_
00038 #define OMPL_ROS_RPY_IK_STATE_TRANSFORMER_H_
00039 
00040 // OMPL ROS Interface
00041 #include <ompl_ros_interface/state_transformers/ompl_ros_ik_state_transformer.h>
00042 #include <ompl_ros_interface/helpers/ompl_ros_conversions.h>
00043 
00044 // Kinematics
00045 #include <pluginlib/class_loader.h>
00046 #include <kinematics_base/kinematics_base.h>
00047 
00048 namespace ompl_ros_interface
00049 {
00050 class OmplRosRPYIKStateTransformer : public OmplRosIKStateTransformer
00051 {
00052 public:
00053   /* @brief Default constructor
00054      @param state_space - The state space that the planner is operating on
00055      @param physical_joint_model_group - The "physical" joint model group that the planner is operating on
00056   */
00057   OmplRosRPYIKStateTransformer(const ompl::base::StateSpacePtr &state_space,
00058                                const planning_models::KinematicModel::JointModelGroup* physical_joint_model_group) 
00059   : OmplRosIKStateTransformer(state_space,physical_joint_model_group){};
00060 
00061   ~OmplRosRPYIKStateTransformer(){}
00062     
00063   /* @brief Custom initialization can be performed here
00064    */ 
00065   virtual bool initialize();
00066 
00067   /* @brief Configure the transformer when a request is received. This is typically a one time configuration 
00068      for each planning request.
00069    */ 
00070   virtual bool configureOnRequest(const arm_navigation_msgs::GetMotionPlan::Request &request,
00071                                   arm_navigation_msgs::GetMotionPlan::Response &response);
00072 
00073   /* @brief Compute the inverse transform (from planning state to physical state)
00074    */ 
00075   virtual bool inverseTransform(const ompl::base::State &ompl_state,
00076                                 arm_navigation_msgs::RobotState &robot_state);
00077 
00078   /* @brief Compute the forward transform (from physical state to planning state)
00079    */ 
00080   virtual bool forwardTransform(const arm_navigation_msgs::RobotState &robot_state,
00081                                 ompl::base::State &ompl_state);
00082 
00083   /* 
00084      @brief Get a default physical state
00085   */ 
00086   virtual arm_navigation_msgs::RobotState getDefaultState();
00087   
00088 private:
00089 
00090   int real_vector_index_;
00091   arm_navigation_msgs::RobotState seed_state_, solution_state_;
00092   int x_index_, y_index_, z_index_, pitch_index_, roll_index_, yaw_index_;  
00093   boost::shared_ptr<ompl::base::ScopedState<ompl::base::CompoundStateSpace> > scoped_state_;
00094 
00095   ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_;
00096   ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_;
00097 
00098   void omplStateToPose(const ompl::base::State &ompl_state,
00099                        geometry_msgs::Pose &pose);
00100 
00101   double generateRandomNumber(const double &min, const double &max);
00102   void generateRandomState(arm_navigation_msgs::RobotState &robot_state);
00103 
00104 
00105 };
00106 }
00107 
00108 #endif //OMPL_ROS_RPY_IK_STATE_TRANSFORMER_H_


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Mon Dec 2 2013 12:38:54