Skip to content

Commit b21c529

Browse files
authored
Merge branch 'master' into add-missing-ros_environment
2 parents ea7296c + 827c61a commit b21c529

File tree

8 files changed

+60
-10
lines changed

8 files changed

+60
-10
lines changed

.github/workflows/config.yml

+3
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,9 @@ on:
44
- master
55
pull_request:
66

7+
env:
8+
ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true
9+
710
jobs:
811
ros:
912
runs-on: ubuntu-latest

doc/jsk_pcl_ros/nodes/hinted_plane_detector.md

+4
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,10 @@ Algorithm is:
4949
## Parameters
5050

5151
### Parameters for detecting hint plane
52+
* `~synchronize` (Double, default: `True`)
53+
54+
Enable time synchronization of input topics
55+
5256
* `~hint_outlier_threashold` (Double, default: `0.1`)
5357

5458
Outlier threshold to detect hint plane using RANSAC

jsk_pcl_ros/cfg/HintedPlaneDetector.cfg

+1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ from math import pi
99

1010
gen = ParameterGenerator ()
1111

12+
gen.add('synchronize', bool_t, 0, 'Enable synchronization of input topics', True)
1213
gen.add("hint_outlier_threashold", double_t, 0, "outlier threshold to detect hint plane", 0.1, 0.0, 1.0)
1314
gen.add("hint_max_iteration", int_t, 0, "max iteration to detect hint plane", 100, 1, 10000)
1415
gen.add("hint_min_size", int_t, 0, "minimum number of inliers included in hint plane", 100, 0, 1000)

jsk_pcl_ros/include/jsk_pcl_ros/hinted_plane_detector.h

+5
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,7 @@ namespace jsk_pcl_ros {
6666
virtual void onInit();
6767
virtual void subscribe();
6868
virtual void unsubscribe();
69+
virtual void setHintCloud(const sensor_msgs::PointCloud2::ConstPtr& msg);
6970
virtual void detect(
7071
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
7172
const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg);
@@ -124,10 +125,14 @@ namespace jsk_pcl_ros {
124125
ros::Publisher pub_euclidean_filtered_indices_;
125126
boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
126127
boost::mutex mutex_;
128+
ros::Subscriber sub_cloud_single_;
129+
ros::Subscriber sub_hint_cloud_single_;
130+
sensor_msgs::PointCloud2::ConstPtr hint_cloud_;
127131

128132
////////////////////////////////////////////////////////
129133
// parameters
130134
////////////////////////////////////////////////////////
135+
bool synchronize_;
131136
double hint_outlier_threashold_;
132137
int hint_max_iteration_;
133138
int hint_min_size_;

jsk_pcl_ros/src/hinted_plane_detector_nodelet.cpp

+42-8
Original file line numberDiff line numberDiff line change
@@ -97,24 +97,40 @@ namespace jsk_pcl_ros {
9797

9898
void HintedPlaneDetector::subscribe()
9999
{
100-
sub_cloud_.subscribe(*pnh_, "input", 1);
101-
sub_hint_cloud_.subscribe(*pnh_, "input/hint/cloud", 1);
102-
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
103-
sync_->connectInput(sub_cloud_, sub_hint_cloud_);
104-
sync_->registerCallback(boost::bind(&HintedPlaneDetector::detect,
105-
this, _1, _2));
100+
if (synchronize_) {
101+
sub_cloud_.subscribe(*pnh_, "input", 1);
102+
sub_hint_cloud_.subscribe(*pnh_, "input/hint/cloud", 1);
103+
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
104+
sync_->connectInput(sub_cloud_, sub_hint_cloud_);
105+
sync_->registerCallback(
106+
boost::bind(&HintedPlaneDetector::detect, this, _1, _2));
107+
} else {
108+
sub_hint_cloud_single_ = pnh_->subscribe<sensor_msgs::PointCloud2>(
109+
"input/hint/cloud", 1, &HintedPlaneDetector::setHintCloud, this);
110+
sub_cloud_single_ = pnh_->subscribe<sensor_msgs::PointCloud2>(
111+
"input", 1,
112+
boost::bind(&HintedPlaneDetector::detect, this, _1,
113+
boost::ref(hint_cloud_)));
114+
}
106115
}
107116

108117
void HintedPlaneDetector::unsubscribe()
109118
{
110-
sub_cloud_.unsubscribe();
111-
sub_hint_cloud_.unsubscribe();
119+
if (synchronize_) {
120+
sub_cloud_.unsubscribe();
121+
sub_hint_cloud_.unsubscribe();
122+
} else {
123+
sub_cloud_single_.shutdown();
124+
sub_hint_cloud_single_.shutdown();
125+
}
112126
}
113127

114128
void HintedPlaneDetector::configCallback(
115129
Config &config, uint32_t level)
116130
{
117131
boost::mutex::scoped_lock lock(mutex_);
132+
const bool need_resubscribe = synchronize_ != config.synchronize;
133+
synchronize_ = config.synchronize;
118134
hint_outlier_threashold_ = config.hint_outlier_threashold;
119135
hint_max_iteration_ = config.hint_max_iteration;
120136
hint_min_size_ = config.hint_min_size;
@@ -131,6 +147,18 @@ namespace jsk_pcl_ros {
131147
enable_normal_filtering_ = config.enable_normal_filtering;
132148
enable_distance_filtering_ = config.enable_distance_filtering;
133149
enable_density_filtering_ = config.enable_density_filtering;
150+
if (need_resubscribe && isSubscribed()) {
151+
unsubscribe();
152+
subscribe();
153+
}
154+
}
155+
156+
void HintedPlaneDetector::setHintCloud(
157+
const sensor_msgs::PointCloud2::ConstPtr &msg)
158+
159+
{
160+
hint_cloud_ = msg;
161+
NODELET_DEBUG("hint cloud is set");
134162
}
135163

136164
void HintedPlaneDetector::detect(
@@ -139,6 +167,12 @@ namespace jsk_pcl_ros {
139167
{
140168
vital_checker_->poke();
141169
boost::mutex::scoped_lock lock(mutex_);
170+
if (!hint_cloud_msg) {
171+
NODELET_WARN_THROTTLE(
172+
10.0,
173+
"hint cloud is not received. Set hint cloud or enable 'synchronize'");
174+
return;
175+
}
142176
pcl::PointCloud<pcl::PointNormal>::Ptr
143177
input_cloud (new pcl::PointCloud<pcl::PointNormal>);
144178
pcl::PointCloud<pcl::PointXYZ>::Ptr

jsk_recognition_utils/CMakeLists.txt

+2-1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ endif(CCACHE_FOUND)
1212
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
1313
## is used, also find other catkin packages
1414
find_package(catkin REQUIRED COMPONENTS
15+
cv_bridge
1516
dynamic_reconfigure
1617
jsk_recognition_msgs
1718
pcl_ros
@@ -52,7 +53,7 @@ generate_dynamic_reconfigure_options(
5253
catkin_package(
5354
INCLUDE_DIRS include
5455
LIBRARIES jsk_recognition_utils
55-
CATKIN_DEPENDS jsk_recognition_msgs pcl_ros visualization_msgs message_runtime
56+
CATKIN_DEPENDS cv_bridge jsk_recognition_msgs pcl_ros visualization_msgs message_runtime
5657
)
5758

5859
# Cythonize pyx files

jsk_recognition_utils/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
<buildtool_depend>catkin</buildtool_depend>
1818
<build_depend>ros_environment</build_depend>
19+
<build_depend>cv_bridge</build_depend>
1920
<build_depend condition="$ROS_PYTHON_VERSION==2">cython</build_depend>
2021
<build_depend condition="$ROS_PYTHON_VERSION==3">cython3</build_depend>
2122
<build_depend>eigen_conversions</build_depend>
@@ -36,6 +37,7 @@
3637
<build_depend>visualization_msgs</build_depend>
3738
<build_depend>yaml-cpp</build_depend>
3839
<build_depend>message_generation</build_depend>
40+
<exec_depend>cv_bridge</exec_depend>
3941
<exec_depend>eigen_conversions</exec_depend>
4042
<exec_depend>geometry_msgs</exec_depend>
4143
<exec_depend>image_geometry</exec_depend>

0 commit comments

Comments
 (0)