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

Use DiagnosticTransport instead of ConnectionBasedTransport #2667

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions jsk_pcl_ros/scripts/color_histogram_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from matplotlib import pyplot as plt
from matplotlib import gridspec
import rospy
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from jsk_recognition_msgs.msg import ColorHistogram, ColorHistogramArray
from sensor_msgs.msg import Image
from jsk_pcl_ros.cfg import ColorHistogramVisualizerConfig as Config
Expand All @@ -24,7 +24,7 @@
IMG_HEIGHT=600


class ColorHistogramVisualizer(ConnectionBasedTransport):
class ColorHistogramVisualizer(DiagnosticTransport):
def __init__(self):
super(ColorHistogramVisualizer, self).__init__()

Expand Down Expand Up @@ -62,6 +62,7 @@ def get_hsv_color_map_2d(self):
return hsv_map

def callback(self, msg):
self.vital_checker.poke()
if self.histogram_policy == Config.ColorHistogramVisualizer_HUE:
img = self.plot_hist_hue(msg.histogram)
elif self.histogram_policy == Config.ColorHistogramVisualizer_HUE_AND_SATURATION:
Expand All @@ -76,6 +77,7 @@ def callback(self, msg):
rospy.logerr("Failed to convert image: %s" % str(e))

def callback_array(self, msg):
self.vital_checker.poke()
if 0 <= self.histogram_index < len(msg.histograms):
self.callback(msg.histograms[self.histogram_index])
else:
Expand Down
6 changes: 3 additions & 3 deletions jsk_pcl_ros/scripts/detect_graspable_poses_pcabase.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,11 @@
import tf.transformations

from geometry_msgs.msg import Pose, PoseArray
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from sensor_msgs.msg import PointCloud2
from sklearn.decomposition import PCA

class DetectGraspablePosesPcabase(ConnectionBasedTransport):
class DetectGraspablePosesPcabase(DiagnosticTransport):

def __init__(self):

Expand All @@ -32,7 +32,7 @@ def unsubscribe(self):
self.sub.unregister()

def callback(self, point_cloud):

self.vital_checker.poke()
points = np.array(list(pc2.read_points(point_cloud, skip_nans=True)))

interval_m = self.interval_m
Expand Down
5 changes: 3 additions & 2 deletions jsk_pcl_ros/scripts/extract_top_polygon_likelihood.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
#!/usr/bin/env python

import rospy
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from jsk_recognition_msgs.msg import PolygonArray, ModelCoefficientsArray
from pcl_msgs.msg import ModelCoefficients
from geometry_msgs.msg import PolygonStamped
import message_filters
from dynamic_reconfigure.server import Server
from jsk_pcl_ros.cfg import ExtractTopPolygonLikelihoodConfig

class ExtractTopPolygonLikelihood(ConnectionBasedTransport):
class ExtractTopPolygonLikelihood(DiagnosticTransport):
def __init__(self):
super(ExtractTopPolygonLikelihood, self).__init__()
self._srv = Server(ExtractTopPolygonLikelihoodConfig, self.config_callback)
Expand All @@ -27,6 +27,7 @@ def unsubscribe(self):
self._sub.sub.unregister()
self._sub_coef.sub.unregister()
def callback(self, msg, msg_coef):
self.vital_checker.poke()
if len(msg.polygons) > 0:
#self._pub.publish(msg.histograms[0])
max_index = max(xrange(len(msg.polygons)), key=lambda i: msg.likelihood[i])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
from jsk_recognition_msgs.msg import BoundingBox
import jsk_recognition_utils
import rospy
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport


class EvaluateBoxSegmentationByGTBox(ConnectionBasedTransport):
class EvaluateBoxSegmentationByGTBox(DiagnosticTransport):

def __init__(self):
super(EvaluateBoxSegmentationByGTBox, self).__init__()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
from jsk_recognition_msgs.msg import Accuracy
from jsk_recognition_msgs.msg import BoundingBox
import jsk_recognition_utils
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import rospy
from visualization_msgs.msg import MarkerArray


class EvaluateVoxelSegmentationByGTBox(ConnectionBasedTransport):
class EvaluateVoxelSegmentationByGTBox(DiagnosticTransport):

def __init__(self):
super(EvaluateVoxelSegmentationByGTBox, self).__init__()
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/aws_detect_faces.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from dynamic_reconfigure.server import Server
from jsk_perception.cfg import AWSDetectFacesConfig

from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from geometry_msgs.msg import PoseArray, Pose, Point
from sensor_msgs.msg import CompressedImage, Image
from opencv_apps.msg import FaceArrayStamped, Face, Rect
Expand Down Expand Up @@ -56,7 +56,7 @@
]


class DetectFaces(ConnectionBasedTransport):
class DetectFaces(DiagnosticTransport):

def __init__(self):
super(self.__class__, self).__init__()
Expand Down Expand Up @@ -160,6 +160,7 @@ def process_attributes(self, text, img, bbox):
self.offset += 16

def image_callback(self, image):
self.vital_checker.poke()
start_time = rospy.Time.now()
# decode compressed image
np_arr = np.fromstring(image.data, np.uint8)
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/binpack_rect_array.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

import cv_bridge
from jsk_recognition_utils.depth import split_fore_background
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from jsk_recognition_msgs.msg import RectArray, Rect
import message_filters
import rospy
Expand Down Expand Up @@ -93,7 +93,7 @@ def grow_down(self, w, h):
# def fuga(msg):
# print "~input/rect_array", msg.header.stamp.to_sec()

class BinPack(ConnectionBasedTransport):
class BinPack(DiagnosticTransport):
def __init__(self):
super(BinPack, self).__init__()
self.pub_ = self.advertise('~output', Image, queue_size=10)
Expand All @@ -113,6 +113,7 @@ def unsubscribe(self):
self.sub_.sub.unregister()
self.sub_rects_.sub.unregister()
def _apply(self, img_msg, rects):
self.vital_checker.poke()
bridge = cv_bridge.CvBridge()
img = bridge.imgmsg_to_cv2(img_msg)
root_rect, blocks = self.bin_pack(rects)
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/bof_histogram_extractor.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
import cv_bridge
from jsk_recognition_msgs.msg import VectorArray
from jsk_recognition_utils import decompose_descriptors_with_label
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import message_filters
from posedetection_msgs.msg import Feature0D
from sensor_msgs.msg import Image
import rospy


class BoFHistogramExtractor(ConnectionBasedTransport):
class BoFHistogramExtractor(DiagnosticTransport):
def __init__(self):
super(BoFHistogramExtractor, self).__init__()

Expand Down Expand Up @@ -67,6 +67,7 @@ def unsubscribe(self):
self._sub_label.unregister()

def _apply(self, feature_msg, label_msg):
self.vital_checker.poke()
bridge = cv_bridge.CvBridge()
label = bridge.imgmsg_to_cv2(label_msg)
desc = np.array(feature_msg.descriptors)
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/depth_image_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,13 @@
import cv_bridge
from dynamic_reconfigure.server import Server
from jsk_perception.cfg import DepthImageFilterConfig as Config
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import numpy as np
import rospy
from sensor_msgs.msg import Image


class DepthImageFilter(ConnectionBasedTransport):
class DepthImageFilter(DiagnosticTransport):

def __init__(self):
super(DepthImageFilter, self).__init__()
Expand All @@ -32,6 +32,7 @@ def config_callback(self, config, level):
return config

def callback(self, depth_img_msg):
self.vital_checker.poke()
bridge = self.bridge

supported_encodings = {'16UC1', '32FC1'}
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/draw_classification_result.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,15 @@
import cv_bridge
from distutils.version import LooseVersion
from jsk_recognition_msgs.msg import ClassificationResult
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import message_filters
import numpy as np
import rospy
from sensor_msgs.msg import Image
from jsk_recognition_utils.color import labelcolormap


class DrawClassificationResult(ConnectionBasedTransport):
class DrawClassificationResult(DiagnosticTransport):

def __init__(self):
super(self.__class__, self).__init__()
Expand All @@ -35,6 +35,7 @@ def unsubscribe(self):
self.sub_img.unregister()

def _draw(self, cls_msg, imgmsg):
self.vital_checker.poke()
bridge = cv_bridge.CvBridge()
rgb = bridge.imgmsg_to_cv2(imgmsg, desired_encoding='rgb8')

Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/draw_rects.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from jsk_recognition_msgs.msg import RectArray
from jsk_recognition_utils.color import labelcolormap
from jsk_recognition_utils.put_text import put_text_to_image
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from jsk_topic_tools import warn_no_remap
import message_filters
import numpy as np
Expand All @@ -19,7 +19,7 @@
from jsk_perception.cfg import DrawRectsConfig


class DrawRects(ConnectionBasedTransport):
class DrawRects(DiagnosticTransport):

def __init__(self):
super(DrawRects, self).__init__()
Expand Down Expand Up @@ -94,6 +94,7 @@ def unsubscribe(self):
sub.sub.unregister()

def draw_rects_callback(self, img_msg, rects_msg, class_msg=None):
self.vital_checker.poke()
bridge = cv_bridge.CvBridge()
cv_img = bridge.imgmsg_to_cv2(img_msg, desired_encoding='bgr8')

Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/extract_image_channel.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import cv_bridge
import dynamic_reconfigure.server
from jsk_perception.cfg import ExtractImageChannelConfig
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
from jsk_topic_tools.log_utils import logwarn_throttle
import rospy
from sensor_msgs.msg import Image
Expand All @@ -34,7 +34,7 @@ def encoding_to_dtype_with_channels(self, encoding):
raise cv_bridge.CvBridgeError(e)


class ExtractImageChannel(ConnectionBasedTransport):
class ExtractImageChannel(DiagnosticTransport):

def __init__(self):
super(self.__class__, self).__init__()
Expand All @@ -53,6 +53,7 @@ def unsubscribe(self):
self.sub.unregister()

def _callback(self, imgmsg):
self.vital_checker.poke()
if self.channel < 0:
return
bridge = CvBridgeArbitraryChannels()
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/face_pose_estimation.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

import cv_bridge
from dynamic_reconfigure.server import Server
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import message_filters
import rospy
import tf.transformations as T
Expand Down Expand Up @@ -211,7 +211,7 @@ def __call__(self, imgs):
return self.forward(imgs)


class FacePoseEstimator(ConnectionBasedTransport):
class FacePoseEstimator(DiagnosticTransport):
def __init__(self):
super(FacePoseEstimator, self).__init__()

Expand Down Expand Up @@ -278,6 +278,7 @@ def unsubscribe(self):
s.unregister()

def callback(self, img, pose2d, pose3d):
self.vital_checker.poke()
header = img.header
try:
img = self.cv_bridge.imgmsg_to_cv2(img, "bgr8")
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/fast_rcnn.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
from jsk_recognition_utils.chainermodels import VGG16FastRCNN
from jsk_recognition_utils.chainermodels import VGG_CNN_M_1024
from jsk_recognition_utils.nms import nms
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import message_filters
import rospkg
import rospy
Expand All @@ -62,7 +62,7 @@ def img_preprocessing(orig_img, pixel_means, max_size=1000, scale=600):
return img.transpose([2, 0, 1]).astype(np.float32), im_scale


class FastRCNN(ConnectionBasedTransport):
class FastRCNN(DiagnosticTransport):

def __init__(self, model, target_names, pixel_means, use_gpu):
super(FastRCNN, self).__init__()
Expand Down Expand Up @@ -104,6 +104,7 @@ def unsubscribe(self):
self._sub_rects.unregister()

def _detect(self, imgmsg, rects_msg):
self.vital_checker.poke()
bridge = cv_bridge.CvBridge()
im_orig = bridge.imgmsg_to_cv2(imgmsg, desired_encoding='bgr8')
im, im_scale = img_preprocessing(im_orig, self.pixel_means)
Expand Down
5 changes: 3 additions & 2 deletions jsk_perception/node_scripts/fcn_depth_prediction.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
import cv_bridge
from jsk_recognition_utils.chainermodels import FCN8sDepthPrediction
from jsk_recognition_utils.chainermodels import FCN8sDepthPredictionConcatFirst
from jsk_topic_tools import ConnectionBasedTransport
from jsk_topic_tools import DiagnosticTransport
import message_filters
import rospy
from sensor_msgs.msg import Image
Expand All @@ -55,7 +55,7 @@ def colorize_depth(depth, min_value=None, max_value=None):
return colorized


class FCNDepthPrediction(ConnectionBasedTransport):
class FCNDepthPrediction(DiagnosticTransport):

def __init__(self):
super(self.__class__, self).__init__()
Expand Down Expand Up @@ -134,6 +134,7 @@ def transform_depth(self, depth):
return depth_viz_bgr

def _cb(self, img_msg, depth_msg):
self.vital_checker.poke()
br = cv_bridge.CvBridge()
bgr_img = br.imgmsg_to_cv2(img_msg, desired_encoding='bgr8')
depth_img = br.imgmsg_to_cv2(depth_msg, desired_encoding='passthrough')
Expand Down
Loading