Skip to content

Commit

Permalink
empty implementation for pure virtual methods
Browse files Browse the repository at this point in the history
PlanningRequestAdapter::initialize() is now pure virtual so we have
to provide an empty implementation on each subclass.

See also moveit/moveit#1621
  • Loading branch information
Bjar Ne committed Nov 13, 2019
1 parent a85789b commit 206e79e
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,11 @@ template<typename T>
}
; // original FilterBase method

/**
* Empty implementation of pure virtual function
*/
virtual void initialize(const ros::NodeHandle& node_handle) override {}

protected:

/**
Expand Down
7 changes: 6 additions & 1 deletion industrial_trajectory_filters/src/add_smoothing_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,12 @@ class AddSmoothingFilter : public planning_request_adapter::PlanningRequestAdapt
}// end of if successful plan
return result;
};


/*!
* Empty implementation of pure virtual function
*/
virtual void initialize(const ros::NodeHandle& node_handle) override {};


private:
ros::NodeHandle nh_;
Expand Down

0 comments on commit 206e79e

Please sign in to comment.