Skip to content

Commit

Permalink
Update include paths of GPL
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 11, 2025
1 parent ec19b21 commit 28bb1b0
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion include/control_filters/exponential_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "filters/filter_base.hpp"

#include "control_toolbox/filters.hpp"
#include "exponential_filter_parameters.hpp"
#include "control_toolbox/exponential_filter_parameters.hpp"

namespace control_filters
{
Expand Down
2 changes: 1 addition & 1 deletion include/control_filters/low_pass_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "geometry_msgs/msg/wrench_stamped.hpp"

#include "control_toolbox/low_pass_filter.hpp"
#include "low_pass_filter_parameters.hpp"
#include "control_toolbox/low_pass_filter_parameters.hpp"

namespace control_filters
{
Expand Down
2 changes: 1 addition & 1 deletion include/control_filters/rate_limiter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "filters/filter_base.hpp"

#include "control_toolbox/rate_limiter.hpp"
#include "rate_limiter_parameters.hpp"
#include "control_toolbox/rate_limiter_parameters.hpp"

namespace control_filters
{
Expand Down

0 comments on commit 28bb1b0

Please sign in to comment.