filter_base.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Southwest Research Institute, nor the names
16  * of its contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef FILTER_BASE_H_
33 #define FILTER_BASE_H_
34 
35 #include <typeinfo>
36 #include "ros/assert.h"
37 #include "ros/console.h"
38 #include "ros/ros.h"
40 #include <moveit/version.h>
42 
44 {
45 
52 {
53 
58  struct Request
59  {
60  trajectory_msgs::JointTrajectory trajectory;
61  } request;
62 };
63 
123 template<typename T>
125  {
126  public:
127 
132  planning_request_adapter::PlanningRequestAdapter(), nh_("~"), configured_(false), filter_type_("FilterBase"), filter_name_(
133  "Unimplemented")
134  {
135 
136  }
137 
141  virtual ~FilterBase()
142  {
143  }
144  ;
145 
154  virtual bool update(const T& data_in, T& data_out)=0;
155 
160  std::string getType()
161  {
162  return filter_type_;
163  }
164  ;
165 
170  inline const std::string& getName()
171  {
172  return filter_name_;
173  }
174  ; // original FilterBase method
175 
176  protected:
177 
178 #if MOVEIT_VERSION_MAJOR >= 1 && MOVEIT_VERSION_MINOR >= 1
179 
182  virtual void initialize(const ros::NodeHandle& node_handle) override
183  {
184  nh_ = node_handle;
185  // configuration is done lazyly later
186  configured_ = false;
187  }
188 #endif
189 
195  virtual bool configure()=0;
196 
200  std::string filter_name_;
201 
205  std::string filter_type_;
206 
211 
216 
217  protected:
218 
227  virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene,
230  std::vector<std::size_t> &added_path_index) const
231  {
232 
233  // non const pointer to this
235 
236  // calling the configure method
237  if (!configured_ && p->configure())
238  {
239  p->configured_ = true;
240  }
241 
242  // moveit messages for saving trajectory data
243  moveit_msgs::RobotTrajectory robot_trajectory_in, robot_trajectory_out;
244  MessageAdapter trajectory_in, trajectory_out; // mapping structures
245 
246  // calling planner first
247  bool result = planner(planning_scene, req, res);
248 
249  // applying filter to planned trajectory
250  if (result && res.trajectory_)
251  {
252  // mapping arguments into message adapter struct
253  res.trajectory_->getRobotTrajectoryMsg(robot_trajectory_in);
254  trajectory_in.request.trajectory = robot_trajectory_in.joint_trajectory;
255 
256  // applying arm navigation filter to planned trajectory
257  if(!p->update(trajectory_in, trajectory_out))
258  {
259  return false;
260  }
261 
262  // saving filtered trajectory into moveit message.
263  robot_trajectory_out.joint_trajectory = trajectory_out.request.trajectory;
264  res.trajectory_->setRobotTrajectoryMsg(planning_scene->getCurrentState(), robot_trajectory_out);
265 
266  }
267 
268  return result;
269  }
270 
275  virtual std::string getDescription() const
276  {
277  // non const pointer to this
279 
280  std::stringstream ss;
281  ss << "Trajectory filter '" << p->getName() << "' of type '" << p->getType() << "'";
282  return ss.str();
283  }
284  };
285 
286 }
287 
288 #endif /* FILTER_BASE_H_ */
std::string getType()
Original FilterBase method, return filter type.
Definition: filter_base.h:160
robot_trajectory::RobotTrajectoryPtr trajectory_
Arm navigation message type for trajectory filter.
Definition: filter_base.h:58
struct industrial_trajectory_filters::MessageAdapter::Request request
ROSCONSOLE_DECL void initialize()
ros::NodeHandle nh_
Internal node handle (used for parameter lookup)
Definition: filter_base.h:215
std::string filter_name_
filter name
Definition: filter_base.h:200
const std::string & getName()
Original FitlerBase Method.
Definition: filter_base.h:170
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
Moveit Planning Request Adapter method. This basic implementation of the adaptAndPlan method calls th...
Definition: filter_base.h:227
bool configured_
Holds filter configuration state.
Definition: filter_base.h:210
This version of the FilterBase<T> can be used to encapsulate the functionality from an arm navigation...
Definition: filter_base.h:124
moveit_msgs::MotionPlanRequest MotionPlanRequest
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
trajectory_msgs::JointTrajectory trajectory
Definition: filter_base.h:60
Message Adapter structure serves as a stand-in for the arm navigation message type with which the fil...
Definition: filter_base.h:51
virtual std::string getDescription() const
Return description string.
Definition: filter_base.h:275
virtual bool configure()=0
FilterBase method for the sub class to configure the filter This function must be implemented in the ...
virtual bool update(const T &data_in, T &data_out)=0
Update the filter and return the data separately. This function must be implemented in the derived cl...


industrial_trajectory_filters
Author(s): Shaun Edwards, Jorge Nicho
autogenerated on Mon Feb 28 2022 22:34:31