ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Setting parameters for mean filter

asked 2018-03-07 23:01:33 -0500

aditya gravatar image

updated 2018-03-08 03:07:53 -0500

I am trying to use the ROS filters to low-pass filter data from a joysitck using the mean filter. I have a node that accepts the commands from the joystick on the "/joy" topic, filters the data, and publishes on another topic. When I try to setup the filters, they always fail with the error :

MultiChannelMeanFilter did not find param number_of_observations

I tried to load the YAML file with the filter configurations (as shown here) in the global namespace, as well as in the namespace of the node using roslaunch, but neither seems to work.

The code I am using to configure the filters:

    class JoystickRelay{
        public:
                JoystickRelay();

        private:
                ros::NodeHandle nh_;
                ros::NodeHandle pnh_;
                ros::Publisher cmd_pub_;
                ros::Subscriber vel_sub_;

                bool enable_filter_;

                void velCallback(const sensor_msgs::Joy::ConstPtr& joy);
                filters::MultiChannelMeanFilter<double> filter_;
};

JoystickRelay::JoystickRelay(): pnh_(ros::NodeHandle("~")), enable_filter_(false) {


        cmd_pub_ = nh_.advertise<std_msgs::Float64MultiArray>("command", 100);
        vel_sub_ = nh_.subscribe("/joy", 1, &JoystickRelay::velCallback, this);

        // Check if filtering is enabled        
        if(pnh_.getParam("filter", enable_filter_)){
                if(enable_filter_){
                        filter_.configure(); // Configure the filter
                }
        }
}

Am I missing something while configuring the filters?

edit retag flag offensive close merge delete

Comments

If you post your launch file & .yaml file it might be easier to troubleshoot. You could also try running some of the test filters in this repo.

stevejp gravatar image stevejp  ( 2018-03-08 06:42:10 -0500 )edit

Thanks stevejp for pointing me in the right direction. I was able to get this working. I have noted the details in the answer to this question.

aditya gravatar image aditya  ( 2018-03-08 22:45:55 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-03-08 22:44:38 -0500

aditya gravatar image

The code and other relevant details are being added here for anybody else who might be facing the same problem.

joy_filter_node.cpp:

#include "filters/mean.h"

class JoystickRelay {
    public:
        JoystickRelay();

    private:
        ros::NodeHandle pnh_;

        filters::MultiChannelFilterBase<double> filter_;
}

JoystickRelay::JoystickRelay() : pnh_(ros::NodeHandle("~")) {

        filter_ = new filters::MultiChannelMeanFilter<double>
        int channels = 2;

        filter_->configure(channels, "FifthOrder", pnh_);

        // Add the other initialization code
}

Notice that the object "filter_" is a pointer to the base class "filters::MultiChannelFilterBase". The private node handle "pnh_" is used for configuration as the parameters from the config file are loaded in the private namespace of the node.

The configuration file -- filter.yaml :

FifthOrder:
  name : my_filter
  type: MultiChannelMeanFilterDouble
  params: 
    number_of_observations : 5

And the launch file:

<launch>
  <node name="joystick_relay" pkg="joystick_relay" type="joystick_relay_node"
        output="screen" ns="/robot/position_controller/" >
    <rosparam file="$(find joystick_relay)/config/filter.yaml" command="load" />
  </node>
</launch>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-03-07 23:01:33 -0500

Seen: 703 times

Last updated: Mar 08 '18