Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dev angular interval filter #107

Open
wants to merge 2 commits into
base: kinetic-devel
Choose a base branch
from

Conversation

ulassbin
Copy link

@ulassbin ulassbin commented Mar 3, 2021

Implemented laser angular interval filter and added yaml description in test/test_scan_filter_chain.yaml.

Angular interval filter takes a parameter interval sets in the form of:
interval_sets: "[[0,0.5],[2,3.2],[5,6.5]]"

which will crop the laser scan between the ranges
0 to 0.5
2 to 3.2
5 to 6.5

Also this parameter can be changed from dynamic parameter server.
It is disabled by default. Can be enabled via dynamic parameter server.

Copy link
Contributor

@jonbinney jonbinney left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@ulassbin sorry for the long delay. This filter looks very useful. I've suggested some changes in the code; could you also fix the conflict in the cmakelists?


gen = ParameterGenerator()

gen.add("interval_sets", str_t, 0, "A string parameter", "[[-1,1],[-1.2,-1.1],[0.5,0.8]]")
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

interval_sets could use a better help string. Also what do you think about shortening the name to just intervals? sets sounds discrete.

gen = ParameterGenerator()

gen.add("interval_sets", str_t, 0, "A string parameter", "[[-1,1],[-1.2,-1.1],[0.5,0.8]]")
gen.add("enable", bool_t, 0, "Whether the filter is enabled or not", False)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe remove enable? I can see how it saves a bit of yaml editing during testing, but it might confuse users since none of the other filter types have this option.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the most reasonable default here should be probably be an empty list.

#
# \author Yannick de Hoop

from dynamic_reconfigure.parameter_generator_catkin import *
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for including dynamic_reconfigure for this!

dyn_server_->setCallback(f);


if (!filters::FilterBase<sensor_msgs::LaserScan>::getParam(std::string("interval_sets"), interval_sets_))
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Doesn't dynamic_reconfigure::Server call your callback with default values when you instantiate it? I think it will read the parameter here so you could skip this part. I guess the one downside is that if the user doesn't set a ROS param to override the default values from the .cfg file, you won't know to warn them. But that's usually how dynamically reconfigureable params work in ros, so probably fine?


void reconfigureCB(AngularIntervalFilterConfig& config, uint32_t level)
{
interval_sets_ = config.interval_sets; // th11,th12;th21,th22;th31,th32
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does the interval_sets_ string need to be a member variable? It seems like you could parse it here and only store the intervals_ as doubles.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also it looks like the format in the comment doesn't match what is in the .cfg file. Shouldn't this be [[th11 th12],[th3, th21]...?

else
{
got_intervals_ = false;
ROS_WARN("Failed to calculate intervals: %s", parse_error.c_str());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it would be cleaner here to throw an exception on an error immediately, rather than printing out a warning. (This is what polygon filter does on a bad reconfigure parameter:

throw std::runtime_error("The polygon must be specified as nested list on the parameter server with at least "
)

filtered_scan = input_scan;
double replacement_value = std::numeric_limits<double>::quiet_NaN();
double current_angle = input_scan.angle_min;
if(got_intervals_ && enable_)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Consider making the name of this variable a bit more detailed. Maybe have_valid_intervals?

}


bool parseIntervalString(const std::string& input, std::string& error_return, std::vector<std::vector<double>>& interval)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This function is a bit verbose, but it looks since it has worked in polygon filter, we can leave it alone.

<class name="laser_filters/LaserScanAngularIntervalFilter" type="laser_filters::LaserScanAngularIntervalFilter"
base_class_type="filters::FilterBase<sensor_msgs::LaserScan>">
<description>
This is a filter which filters sensor_msgs::LaserScan messages based on angular intervals.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you add a couple more sentences to the description? Maybe something like For example, if the intervals parameter is ...., then the filter will only allow laser beams whose angle is between .... and ....

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants