$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, 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 the Willow Garage 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 CHOMP_PLANNER_NODE_H_ 00038 #define CHOMP_PLANNER_NODE_H_ 00039 00040 #include <ros/ros.h> 00041 00042 #include <arm_navigation_msgs/GetMotionPlan.h> 00043 #include <arm_navigation_msgs/convert_messages.h> 00044 00045 #include <arm_navigation_msgs/FilterJointTrajectoryWithConstraints.h> 00046 00047 00048 #include <chomp_motion_planner/chomp_parameters.h> 00049 #include <collision_proximity/collision_proximity_space.h> 00050 #include <map> 00051 #include <string> 00052 #include <filters/filter_chain.h> 00053 #include <eigen3/Eigen/Core> 00054 00055 namespace chomp 00056 { 00057 00061 class ChompPlannerNode 00062 { 00063 public: 00067 ChompPlannerNode(ros::NodeHandle node_handle, collision_proximity::CollisionProximitySpace* space); 00068 00072 virtual ~ChompPlannerNode(); 00073 00079 bool init(); 00080 00086 int run(); 00087 00091 bool planKinematicPath(arm_navigation_msgs::GetMotionPlan::Request &req, arm_navigation_msgs::GetMotionPlan::Response &res); 00092 00093 bool filterJointTrajectory(arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request &req, arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response &res); 00094 00095 private: 00096 ros::NodeHandle node_handle_, root_handle_; 00097 ros::ServiceServer plan_kinematic_path_service_; 00099 ros::ServiceServer filter_joint_trajectory_service_; 00101 planning_environment::CollisionModels* collision_models_; 00102 std::string reference_frame_; 00103 00104 planning_models::KinematicModel* robot_model_; 00105 ChompParameters chomp_parameters_; 00106 collision_proximity::CollisionProximitySpace* collision_proximity_space_; 00107 double trajectory_duration_; 00108 double trajectory_discretization_; 00109 ros::Publisher vis_marker_array_publisher_; 00110 ros::Publisher vis_marker_publisher_; 00111 std::map<std::string, double> joint_velocity_limits_; 00112 bool use_trajectory_filter_; 00113 int maximum_spline_points_; 00114 int minimum_spline_points_; 00115 00116 std::map<std::string, arm_navigation_msgs::JointLimits> joint_limits_; 00117 void getLimits(const trajectory_msgs::JointTrajectory& trajectory, 00118 std::vector<arm_navigation_msgs::JointLimits>& limits_out); 00119 00120 00121 //filters::FilterChain<arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request> filter_constraints_chain_; 00122 ros::ServiceClient filter_trajectory_client_; 00123 00124 inline void jointStateToArray(const sensor_msgs::JointState &joint_state, std::string& planning_group_name, Eigen::MatrixXd::RowXpr joint_array) 00125 { 00126 std::map<std::string, planning_models::KinematicModel::JointModelGroup*> groupMap = robot_model_->getJointModelGroupMap(); 00127 const planning_models::KinematicModel::JointModelGroup* group = groupMap[planning_group_name]; 00128 std::vector<const planning_models::KinematicModel::JointModel*> models = group->getJointModels(); 00129 00130 for(unsigned int i=0; i < joint_state.position.size(); i++) 00131 { 00132 for(size_t j = 0; j < models.size(); j++) 00133 { 00134 if(models[j]->getName() == joint_state.name[i]) 00135 { 00136 joint_array(0, j) = joint_state.position[i]; 00137 } 00138 } 00139 } 00140 } 00141 00142 }; 00143 00144 } 00145 00146 #endif /* CHOMP_PLANNER_NODE_H_ */