@@ -97,24 +97,40 @@ namespace jsk_pcl_ros {
97
97
98
98
void HintedPlaneDetector::subscribe ()
99
99
{
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
+ }
106
115
}
107
116
108
117
void HintedPlaneDetector::unsubscribe ()
109
118
{
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
+ }
112
126
}
113
127
114
128
void HintedPlaneDetector::configCallback (
115
129
Config &config, uint32_t level)
116
130
{
117
131
boost::mutex::scoped_lock lock (mutex_);
132
+ const bool need_resubscribe = synchronize_ != config.synchronize ;
133
+ synchronize_ = config.synchronize ;
118
134
hint_outlier_threashold_ = config.hint_outlier_threashold ;
119
135
hint_max_iteration_ = config.hint_max_iteration ;
120
136
hint_min_size_ = config.hint_min_size ;
@@ -131,6 +147,18 @@ namespace jsk_pcl_ros {
131
147
enable_normal_filtering_ = config.enable_normal_filtering ;
132
148
enable_distance_filtering_ = config.enable_distance_filtering ;
133
149
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" );
134
162
}
135
163
136
164
void HintedPlaneDetector::detect (
@@ -139,6 +167,12 @@ namespace jsk_pcl_ros {
139
167
{
140
168
vital_checker_->poke ();
141
169
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
+ }
142
176
pcl::PointCloud<pcl::PointNormal>::Ptr
143
177
input_cloud (new pcl::PointCloud<pcl::PointNormal>);
144
178
pcl::PointCloud<pcl::PointXYZ>::Ptr
0 commit comments