add_smoothing_filter.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, Southwest Research Institute
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 Southwest Research Institute 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 
00035 /* Author: Chris Lewis */
00036 
00037 #include <moveit/planning_request_adapter/planning_request_adapter.h>
00038 #include <class_loader/class_loader.h>
00039 
00040 #include <industrial_trajectory_filters/smoothing_trajectory_filter.h>
00041 #include <ros/ros.h>  // required for NodeHandle
00042 #include <ros/console.h>
00043 
00044 namespace industrial_trajectory_filters
00045 {
00046 
00047 class AddSmoothingFilter : public planning_request_adapter::PlanningRequestAdapter
00048 {
00049 public:
00050 
00051   static const std::string FILTER_PARAMETER_NAME_; // base name for filter parameters
00052 
00057   AddSmoothingFilter() : planning_request_adapter::PlanningRequestAdapter(), nh_("~")
00058   {
00059       int num_coef;
00060 
00061       // set of default filter coefficients in case paramter, or its associated file, or its syntax is wrong
00062       filter_coef_.push_back(0.25);
00063       filter_coef_.push_back(0.5);
00064       filter_coef_.push_back(1.0);
00065       filter_coef_.push_back(0.5);
00066       filter_coef_.push_back(0.25);
00067 
00068     // see if a new set of filter parameters is on the parameter server, if so, install them
00069     if (!nh_.getParam(FILTER_PARAMETER_NAME_, filter_name_)){
00070       ROS_INFO_STREAM("Param '" << FILTER_PARAMETER_NAME_ << "' was not set. Using default filter values " );
00071     }
00072     else{ // base filter name exists
00073       std::vector<double> temp_coef;
00074       nh_.getParam(filter_name_.c_str(),temp_coef); // no need to check for success
00075       if(temp_coef.size()%2 == 1 && temp_coef.size()>2){ // need to have odd number of coefficients greater than 2
00076         filter_coef_.clear();
00077         for(int i=0; i< (int) temp_coef.size(); i++){ // install the filter coefficients
00078           filter_coef_.push_back(temp_coef[i]);
00079         }
00080       }
00081       else{
00082         ROS_INFO_STREAM("Could not read filter, using default filter coefficients");
00083       }
00084     }
00085     if(!smoothing_filter_.init(filter_coef_))
00086       ROS_ERROR("Initialization error on smoothing filter. Requires an odd number of coeficients");
00087     
00088   };
00089 
00091   ~AddSmoothingFilter(){ };
00092 
00094   virtual std::string getDescription() const { return "Add Smoothing Trajectory Filter"; }
00095 
00103   virtual bool adaptAndPlan(const PlannerFn &planner,
00104                             const planning_scene::PlanningSceneConstPtr& planning_scene,
00105                             const planning_interface::MotionPlanRequest &req,
00106                             planning_interface::MotionPlanResponse &res,
00107                             std::vector<std::size_t> &added_path_index) const
00108   {
00109     // do anything prior to calling the planner here
00110     // ....
00111     // IN this case nothing was done
00112 
00113     // call the nested planner or adapter
00114     bool result = planner(planning_scene, req, res); 
00115 
00116     // do anything after calling the nested planner or adapters here
00117     if (result && res.trajectory_) // successful plan
00118     {
00119       ROS_DEBUG("Running '%s'", getDescription().c_str()); // inform the user 
00120       if (!smoothing_filter_.applyFilter(*res.trajectory_)) {// do the smoothing
00121         ROS_ERROR("Smoothing filter of the solution path failed. Filter Not Initialized ");
00122       }
00123     }// end of if successful plan
00124     return result;
00125   };
00126   
00127 
00128 private:
00129   ros::NodeHandle nh_;
00130   industrial_trajectory_filters::SmoothingTrajectoryFilter smoothing_filter_;
00131   std::string filter_name_;
00132   std::vector<double> filter_coef_;
00133 
00134 };
00135 
00136 const std::string  AddSmoothingFilter::FILTER_PARAMETER_NAME_ = "/move_group/smoothing_filter_name";
00137 
00138 }
00139 
00140 CLASS_LOADER_REGISTER_CLASS(industrial_trajectory_filters::AddSmoothingFilter,
00141                             planning_request_adapter::PlanningRequestAdapter);


industrial_trajectory_filters
Author(s): Shaun Edwards , Jorge Nicho
autogenerated on Tue Jan 17 2017 21:09:57