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 TRAJECTORY_FILTER_SERVER_H_ 00038 #define TRAJECTORY_FILTER_SERVER_H_ 00039 00040 #include <ros/ros.h> 00041 #include <filters/filter_chain.h> 00042 #include <arm_navigation_msgs/FilterJointTrajectory.h> 00043 #include <arm_navigation_msgs/FilterJointTrajectoryWithConstraints.h> 00044 #include <urdf/model.h> 00045 00046 namespace trajectory_filter_server 00047 { 00048 00049 static const int FILTER_JOINT_TRAJECTORY = 0; 00050 static const int FILTER_JOINT_TRAJECTORY_WITH_CONSTRAINTS = 1; 00051 00052 class TrajectoryFilterServer 00053 { 00054 00055 public: 00056 TrajectoryFilterServer(); 00057 virtual ~TrajectoryFilterServer(); 00058 bool init(); 00059 00060 private: 00061 bool filter(arm_navigation_msgs::FilterJointTrajectory::Request &req, 00062 arm_navigation_msgs::FilterJointTrajectory::Response &resp); 00063 00064 bool filterConstraints(arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Request &req, 00065 arm_navigation_msgs::FilterJointTrajectoryWithConstraints::Response &resp); 00066 00067 // void jointTrajectoryToJointTrajectoryWithLimits(const trajectory_msgs::JointTrajectory& joint_traj, 00068 //arm_navigation_msgs::JointTrajectoryWithLimits& waypoint_traj); 00069 00070 void getLimits(const trajectory_msgs::JointTrajectory& trajectory, 00071 std::vector<arm_navigation_msgs::JointLimits>& limits_out); 00072 00073 ros::NodeHandle private_handle_, root_handle_; 00074 ros::ServiceServer filter_service_, filter_constraints_service_; 00075 std::map<std::string, arm_navigation_msgs::JointLimits> joint_limits_; 00076 00077 int service_type_; 00078 00079 filters::FilterChain<arm_navigation_msgs::FilterJointTrajectory> filter_chain_; 00080 filters::FilterChain<arm_navigation_msgs::FilterJointTrajectoryWithConstraints> filter_constraints_chain_; 00081 00082 urdf::Model urdf_model_; 00083 00084 bool loadURDF(); 00085 bool use_safety_limits_; 00086 00087 }; 00088 00089 } 00090 00091 #endif /* TRAJECTORY_FILTER_SERVER_H_ */