Skip to content

Commit

Permalink
[jsk_perception][jsk_pcl_ros_utils][resized_image_transport] Call onI…
Browse files Browse the repository at this point in the history
…nitPostProcess()
  • Loading branch information
nakane11 committed Aug 24, 2022
1 parent 59b5191 commit 1c54016
Show file tree
Hide file tree
Showing 12 changed files with 12 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ namespace jsk_pcl_ros_utils
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (&ColorizeDistanceFromPlane::configCallback, this, _1, _2);
srv_->setCallback (f);
onInitPostProcess();
}

ColorizeDistanceFromPlane::~ColorizeDistanceFromPlane() {
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/delay_pointcloud_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ namespace jsk_pcl_ros_utils
pnh_->param("delay_time", delay_time_, 0.1);
pnh_->param("queue_size", queue_size_, 1000);
pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", queue_size_);
onInitPostProcess();
}

void DelayPointCloud::configCallback(Config &config, uint32_t level)
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/depth_image_error_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ namespace jsk_pcl_ros_utils
ConnectionBasedNodelet::onInit();
pnh_->param("approximate_sync", approximate_sync_, false);
depth_error_publisher_ = advertise<jsk_recognition_msgs::DepthErrorResult>(*pnh_, "output", 1);
onInitPostProcess();
}

DepthImageError::~DepthImageError() {
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/normal_concatenater_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ namespace jsk_pcl_ros_utils
if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
maximum_queue_size_ = 100;
}
onInitPostProcess();
}

NormalConcatenater::~NormalConcatenater() {
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/polygon_appender_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ namespace jsk_pcl_ros_utils
sync_->connectInput(sub_polygon0_, sub_coefficients0_,
sub_polygon1_, sub_coefficients1_);
sync_->registerCallback(boost::bind(&PolygonAppender::callback2, this, _1, _2, _3, _4));
onInitPostProcess();
}

PolygonAppender::~PolygonAppender() {
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/polygon_array_unwrapper_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ namespace jsk_pcl_ros_utils
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind(&PolygonArrayUnwrapper::configCallback, this, _1, _2);
srv_->setCallback(f);
onInitPostProcess();
}

PolygonArrayUnwrapper::~PolygonArrayUnwrapper() {
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros_utils/src/polygon_array_wrapper_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ namespace jsk_pcl_ros_utils
pub_coefficients_array_
= advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_,
"output_coefficients", 1);
onInitPostProcess();
}

PolygonArrayWrapper::~PolygonArrayWrapper() {
Expand Down
2 changes: 1 addition & 1 deletion jsk_perception/src/bounding_box_to_rect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace jsk_perception
pub_ = advertise<jsk_recognition_msgs::RectArray>(*pnh_, "output", 1);
pub_internal_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo>("internal", 1);
sub_box_with_info_.subscribe(*pnh_, "internal", 1);
//onInitPosrPocess();
onInitPostProcess();
}

BoundingBoxToRect::~BoundingBoxToRect() {
Expand Down
1 change: 1 addition & 0 deletions jsk_perception/src/polygon_array_color_likelihood.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ namespace jsk_perception
&PolygonArrayColorLikelihood::configCallback, this, _1, _2);
srv_->setCallback (f);
pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output", 1);
onInitPostProcess();
}

PolygonArrayColorLikelihood::~PolygonArrayColorLikelihood() {
Expand Down
1 change: 1 addition & 0 deletions jsk_perception/src/robot_to_mask_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ namespace jsk_perception
pnh_->param("max_robot_dist", max_robot_dist_, 10.0);
pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
pub_camera_info_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output/info", 1);
onInitPostProcess();
}

void RobotToMaskImage::subscribe()
Expand Down
1 change: 1 addition & 0 deletions resized_image_transport/src/image_processing_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ namespace resized_image_transport
initReconfigure();
initParams();
initPublishersAndSubscribers();
onInitPostProcess();
}

void ImageProcessing::initReconfigure(){
Expand Down
1 change: 1 addition & 0 deletions resized_image_transport/src/log_polar_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ namespace resized_image_transport
initReconfigure();
initParams();
initPublishersAndSubscribers();
onInitPostProcess();
}


Expand Down

0 comments on commit 1c54016

Please sign in to comment.