Go to the documentation of this file.
32 #ifndef FILTER_BASE_H_
33 #define FILTER_BASE_H_
40 #include <moveit/version.h>
154 virtual bool update(
const T& data_in, T& data_out)=0;
178 #if MOVEIT_VERSION_MAJOR >= 1 && MOVEIT_VERSION_MINOR >= 1
230 std::vector<std::size_t> &added_path_index)
const
243 moveit_msgs::RobotTrajectory robot_trajectory_in, robot_trajectory_out;
253 res.
trajectory_->getRobotTrajectoryMsg(robot_trajectory_in);
257 if(!p->
update(trajectory_in, trajectory_out))
280 std::stringstream ss;
281 ss <<
"Trajectory filter '" << p->
getName() <<
"' of type '" << p->
getType() <<
"'";
std::string getType()
Original FilterBase method, return filter type.
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...
FilterBase()
Default constructor.
bool configured_
Holds filter configuration state.
struct industrial_trajectory_filters::MessageAdapter::Request request
virtual std::string getDescription() const
Return description string.
virtual bool configure()=0
FilterBase method for the sub class to configure the filter This function must be implemented in the ...
robot_trajectory::RobotTrajectoryPtr trajectory_
trajectory_msgs::JointTrajectory trajectory
ros::NodeHandle nh_
Internal node handle (used for parameter lookup)
This version of the FilterBase<T> can be used to encapsulate the functionality from an arm navigation...
Arm navigation message type for trajectory filter.
moveit_msgs::MotionPlanRequest MotionPlanRequest
virtual void initialize(const ros::NodeHandle &node_handle)=0
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Message Adapter structure serves as a stand-in for the arm navigation message type with which the fil...
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...
std::string filter_name_
filter name
const std::string & getName()
Original FitlerBase Method.