Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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>
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_;
00052
00057 AddSmoothingFilter() : planning_request_adapter::PlanningRequestAdapter(), nh_("~")
00058 {
00059 int num_coef;
00060
00061
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
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{
00073 std::vector<double> temp_coef;
00074 nh_.getParam(filter_name_.c_str(),temp_coef);
00075 if(temp_coef.size()%2 == 1 && temp_coef.size()>2){
00076 filter_coef_.clear();
00077 for(int i=0; i< (int) temp_coef.size(); i++){
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
00110
00111
00112
00113
00114 bool result = planner(planning_scene, req, res);
00115
00116
00117 if (result && res.trajectory_)
00118 {
00119 ROS_DEBUG("Running '%s'", getDescription().c_str());
00120 if (!smoothing_filter_.applyFilter(*res.trajectory_)) {
00121 ROS_ERROR("Smoothing filter of the solution path failed. Filter Not Initialized ");
00122 }
00123 }
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);