approach_planner.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2013, PAL Robotics, S.L.
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 PAL Robotics, S.L. 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 PLAY_MOTION_APPROACH_PLANNER_H
00038 #define PLAY_MOTION_APPROACH_PLANNER_H
00039 
00040 #include <map>
00041 #include <vector>
00042 
00043 #include <boost/shared_ptr.hpp>
00044 
00045 #include <ros/message_forward.h>
00046 
00047 #include <play_motion/datatypes.h>
00048 
00049 namespace ros
00050 {
00051   class NodeHandle;
00052   class AsyncSpinner;
00053   class CallbackQueue;
00054 }
00055 
00056 namespace trajectory_msgs
00057 {
00058   ROS_DECLARE_MESSAGE(JointTrajectory);
00059 }
00060 
00061 namespace moveit
00062 {
00063   namespace planning_interface
00064   {
00065     class MoveGroup;
00066   }
00067 }
00068 
00069 namespace play_motion
00070 {
00072   class ApproachPlanner
00073   {
00074   public:
00075 
00076     ApproachPlanner(const ros::NodeHandle& nh);
00077 
00079     bool prependApproach(const std::vector<std::string>& joint_names,
00080                          const std::vector<double>&      current_pos,
00081                          bool                            skip_planning,
00082                          const std::vector<TrajPoint>&   traj_in,
00083                                std::vector<TrajPoint>&   traj_out);
00084 
00086     bool needsApproach(const std::vector<double>& current_pos,
00087                        const std::vector<double>& goal_pos);
00088 
00089   private:
00090     typedef moveit::planning_interface::MoveGroup MoveGroup;
00091     typedef boost::shared_ptr<MoveGroup> MoveGroupPtr;
00092     typedef boost::shared_ptr<ros::AsyncSpinner> AsyncSpinnerPtr;
00093     typedef boost::shared_ptr<ros::CallbackQueue> CallbackQueuePtr;
00094     typedef std::vector<std::string> JointNames;
00095     typedef std::map<std::string, double> JointGoal;
00096 
00097     struct PlanningData
00098     {
00099       PlanningData(MoveGroupPtr move_group_ptr);
00100       MoveGroupPtr move_group;
00101       JointNames   sorted_joint_names;
00102     };
00103 
00104     std::vector<PlanningData> planning_data_;
00105     std::vector<std::string> no_plan_joints_;
00106     double joint_tol_; 
00107     double skip_planning_vel_; 
00108     double skip_planning_min_dur_; 
00109     CallbackQueuePtr cb_queue_;
00110     AsyncSpinnerPtr spinner_;
00111     bool planning_disabled_;
00112 
00114     bool computeApproach(const JointNames&                 joint_names,
00115                          const std::vector<double>&        current_pos,
00116                          const std::vector<double>&        goal_pos,
00117                          trajectory_msgs::JointTrajectory& traj);
00118 
00120     bool planApproach(const JointNames&                 joint_names,
00121                       const std::vector<double>&        joint_values,
00122                       MoveGroupPtr                      move_group,
00123                       trajectory_msgs::JointTrajectory& traj);
00125     void combineTrajectories(const JointNames&                  joint_names,
00126                              const std::vector<double>&         current_pos,
00127                              const std::vector<TrajPoint>&      traj_in,
00128                              trajectory_msgs::JointTrajectory&  approach,
00129                              std::vector<TrajPoint>&            traj_out);
00130 
00132     std::vector<MoveGroupPtr> getValidMoveGroups(const JointNames& min_group,
00133                                                  const JointNames& max_group);
00134 
00136     bool isPlanningJoint(const std::string& joint_name) const;
00137 
00139     double noPlanningReachTime(const std::vector<double>& curr_pos,
00140                                const std::vector<double>& goal_pos);
00141   };
00142 
00143 } // namespace
00144 
00145 #endif


play_motion
Author(s): Paul Mathieu
autogenerated on Wed Aug 26 2015 15:29:25