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

[jsk_pcl_ros_utils] add PolygonArrayLikelihoodFilter #2054

Merged
merged 4 commits into from
Jun 14, 2017

Conversation

furushchev
Copy link
Member

Nodelet to filter polygons by likelihood.

@furushchev
Copy link
Member Author

[jsk_pcl_ros_utils] /workspace/ros/ws_jsk_recognition/src/jsk_recognition/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp: In member function 'virtual void jsk_pcl_ros_utils::PolygonArrayLikelihoodFilter::onInit()': 

[jsk_pcl_ros_utils] /workspace/ros/ws_jsk_recognition/src/jsk_recognition/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp:53:67: error: no matching function for call to 'ros::NodeHandle::param(const char [17], bool)' 

[jsk_pcl_ros_utils] /workspace/ros/ws_jsk_recognition/src/jsk_recognition/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp:53:67: note: candidate is: 

[jsk_pcl_ros_utils] /opt/ros/hydro/include/ros/node_handle.h:1912:8: note: template void ros::NodeHandle::param(const string&, T&, const T&) const 

[jsk_pcl_ros_utils] make[2]: *** [CMakeFiles/jsk_pcl_ros_utils.dir/src/polygon_array_likelihood_filter_nodelet.cpp.o] Error 1 

[jsk_pcl_ros_utils] make[2]: *** Waiting for unfinished jobs.... 

[jsk_perception] Scanning dependencies of target bounding_rect_mask_image 

[jsk_pcl_ros_utils] [ 82%] Building CXX object CMakeFiles/jsk_pcl_ros_utils.dir/src/delay_pointcloud_nodelet.cpp.o 

@furushchev furushchev force-pushed the polygonarray-unwrapper branch 2 times, most recently from ce465d4 to 1340bf4 Compare April 18, 2017 04:22
@wkentaro wkentaro assigned wkentaro and unassigned wkentaro Apr 20, 2017

Threshold for filtering polygons.

* ``~negate`` (Bool, default: ``false``)
Copy link
Member

Choose a reason for hiding this comment

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

~negative is better.

Copy link
Member Author

Choose a reason for hiding this comment

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

Fixed!


If ``true``, polygons and coefficients are subscribed and published synchronously.

* ``~min_likelihood`` (Double, default: ``0.5``)
Copy link
Member

Choose a reason for hiding this comment

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

~threshold is better?

Copy link
Member Author

Choose a reason for hiding this comment

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

Fixed!

pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(
*pnh_, "output_polygons", 1);

pnh_->param<bool>(std::string("use_coefficients"), use_coefficients_, true);
Copy link
Member

Choose a reason for hiding this comment

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

std::string is not necessary, no?

Copy link
Member Author

Choose a reason for hiding this comment

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

You are right! I forgot to remove that. Fixed.

this, _1, _2));
} else {
sub_polygons_alone_ = pnh_->subscribe(
"input_polygons", 1, &PolygonArrayLikelihoodFilter::filter, this);
Copy link
Member

Choose a reason for hiding this comment

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

sub_polygons_.registerCallback(&PolygonArrayLIkelihoodFilter::fileter, this);

Copy link
Member Author

Choose a reason for hiding this comment

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

@wkentaro Why this is not allowed? sub_polygons_alone is just a ros::Suscriber not a message_filters::Subscriber.

Copy link
Member

Choose a reason for hiding this comment

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

I mean just it seems better.

Copy link
Member Author

@furushchev furushchev Apr 22, 2017

Choose a reason for hiding this comment

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

@wkentaro
Sorry, I didn't know about that. What is difference between two calls? Is there any performance improvement?

Copy link
Member

Choose a reason for hiding this comment

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

The difference is the necessity of definition of sub_polygons_alone_, and with my method, you don't need to define it, leading less number of member varaibles.

Is there any perfo..

I'm not sure about that.

Copy link
Member Author

Choose a reason for hiding this comment

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

But this is not usual way of message_filers, I think...

Copy link
Member

@wkentaro wkentaro Apr 22, 2017

Choose a reason for hiding this comment

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

Copy link
Member

@wkentaro wkentaro Apr 22, 2017

Choose a reason for hiding this comment

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

boost::mutex::scoped_lock lock(mutex_);
min_likelihood_ = config.min_likelihood;
negate_ = config.negate;
if (queue_size_ != config.queue_size) {
Copy link
Member

Choose a reason for hiding this comment

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

Oh, this is great 👍

Copy link
Member Author

Choose a reason for hiding this comment

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

@wkentaro But I found that the code below is super bad... Fixed anyway, thanks!

Copy link
Member

@k-okada k-okada left a comment

Choose a reason for hiding this comment

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

do we have example launch file for this node?

[jsk_pcl_ros_utils] add docs for polygon_array_likelihood_filter
@furushchev
Copy link
Member Author

do we have example launch file for this node?

@k-okada Thanks for review! I can write sample launch file if #2053 is merged easily. Please could you wait?

@furushchev
Copy link
Member Author

Sorry for late, I updated this PR: added test code and sample launch file.

@k-okada k-okada merged commit 9c3fe55 into jsk-ros-pkg:master Jun 14, 2017
@furushchev furushchev deleted the polygonarray-unwrapper branch June 14, 2017 02:33
@furushchev
Copy link
Member Author

@k-okada Thank you for merging!

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

Successfully merging this pull request may close these issues.

None yet

3 participants