Skip to content

Unable to configure filters #399

@OscarMrZ

Description

@OscarMrZ

Describe the bug
I'm trying to load the GravityCompensation compensation filter into my code. I'm able to load the plugin correctly, both using the FilterChain and standalone (calling getUniqueInstance directly), and it seems all the parameters are correctly set. When I try to configure (either the chain or the filter directly), I get a segmentation fault.

void configure_filter_directly()
{
   pluginlib::UniquePtr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> loaded_filter;

   loaded_filter->configure(
      "sensor_filter_chain.filter1", "gravity_compensation",
      this->get_node_logging_interface(), this->get_node_parameters_interface());
}

Debugging the code with gdb, it seems the issue is coming from filter_base.hpp:105. I wrapped it into two silly prints just to be sure and it seems to be the case:

std::cout << "Calling specific configuring" << std::endl;
configured_ = configure();
std::cout << "called specific configuring" << std::endl;

It never gets to the second print.

This is the stacktrace from gdb

─── Stack ──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────
[0] from 0x0000000000000000
[1] from 0x00005555555634ce in filters::FilterBase<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > >::configure(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> const&, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> const&)+734 at /home/user/exchange/ws/ft_calibration/src/filters/include/filters/filter_base.hpp:106
[2] from 0x000055555556d953 in DummyFilterLoader::configure_filter_directly()+867 at /home/user/exchange/ws/ft_calibration/src/dummy_filter_loader/src/filter_loader.cpp:45
[3] from 0x000055555555f36c in main(int, char**)+188 at /home/user/exchange/ws/ft_calibration/src/dummy_filter_loader/src/filter_loader.cpp:60

I also checked with the control_filters/LowPassFilterDouble and the issue is <the same.

To Reproduce
Steps to reproduce the behavior:

  1. Go to https://github.com/OscarMrZ/dummy_filter_loader/tree/main
  2. Clone into a workspace
  3. Compile normally with colcon
  4. ros2 run dummy_filter_loader dummy_filter_loader --ros-args --params-file src/dummy_filter_loader/params/params.yaml
  5. See the error
GravityCompensation constructor called, this=0x5d492f566280
Calling specific configuring
Stack trace (most recent call last):
#3    Object "", at 0, in
#2    Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7582f298c51f, in
#1    Object "/opt/pal/alum/lib/libbackward.so", at 0x7582f3044372, in backward::SignalHandling::sig_handler(int, siginfo_t*, void*)
#0    Object "/opt/pal/alum/lib/libbackward.so", at 0x7582f3043d11, in
Segmentation fault (Address not mapped to object [(nil)])
[ros2run]: Segmentation fault

Expected behavior
The filter is initialized with its parameters and it's ready to use (aka update can be called on it with data)

Environment (please complete the following information):

  • OS: Ubuntu 22.04
  • Version Humble/Rolling
  • I'm using Humble but all the ROS 2 control packages are targeting the rolling version. This is also the case for control_toolbox, so technically I'm using rolling.

Additional context
I'm exploring this to enable the gravity filter in the force torque sensor, continuing this PR

Metadata

Metadata

Assignees

No one assigned

    Labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions