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 <motion_planning_msgs/GetMotionPlan.h> 00043 #include <motion_planning_msgs/convert_messages.h> 00044 00045 #include <motion_planning_msgs/FilterJointTrajectoryWithConstraints.h> 00046 00047 #include <chomp_motion_planner/chomp_robot_model.h> 00048 #include <chomp_motion_planner/chomp_parameters.h> 00049 #include <chomp_motion_planner/chomp_collision_space.h> 00050 #include <planning_environment/monitors/collision_space_monitor.h> 00051 #include <map> 00052 #include <string> 00053 #include <filters/filter_chain.h> 00054 00055 namespace chomp 00056 { 00057 00061 class ChompPlannerNode 00062 { 00063 public: 00067 ChompPlannerNode(ros::NodeHandle node_handle); 00068 00072 virtual ~ChompPlannerNode(); 00073 00079 bool init(); 00080 00086 int run(); 00087 00091 bool planKinematicPath(motion_planning_msgs::GetMotionPlan::Request &req, motion_planning_msgs::GetMotionPlan::Response &res); 00092 00093 bool filterJointTrajectory(motion_planning_msgs::FilterJointTrajectoryWithConstraints::Request &req, motion_planning_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 planning_environment::CollisionSpaceMonitor *monitor_; 00103 tf::TransformListener tf_; 00104 std::string reference_frame_; 00105 00106 ChompRobotModel chomp_robot_model_; 00107 ChompParameters chomp_parameters_; 00108 ChompCollisionSpace chomp_collision_space_; 00109 double trajectory_duration_; 00110 double trajectory_discretization_; 00111 ros::Publisher vis_marker_array_publisher_; 00112 ros::Publisher vis_marker_publisher_; 00113 std::map<std::string, double> joint_velocity_limits_; 00114 bool use_trajectory_filter_; 00115 int maximum_spline_points_; 00116 int minimum_spline_points_; 00117 00118 std::map<std::string, motion_planning_msgs::JointLimits> joint_limits_; 00119 void getLimits(const trajectory_msgs::JointTrajectory& trajectory, 00120 std::vector<motion_planning_msgs::JointLimits>& limits_out); 00121 00122 //filters::FilterChain<motion_planning_msgs::FilterJointTrajectoryWithConstraints::Request> filter_constraints_chain_; 00123 ros::ServiceClient filter_trajectory_client_; 00124 00125 }; 00126 00127 } 00128 00129 #endif /* CHOMP_PLANNER_NODE_H_ */