Skip to content

Commit

Permalink
As a server (HiroIshida#22)
Browse files Browse the repository at this point in the history
* Define custom service

* Add request handler

* Turn off pubsub

* Add client example

* Enable loading custom image
  • Loading branch information
HiroIshida authored Apr 5, 2022
1 parent eea02b0 commit 29fe219
Show file tree
Hide file tree
Showing 6 changed files with 63 additions and 5 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,11 @@ add_message_files(
SegmentationInfo.msg
)

add_service_files(
FILES
DeticSeg.srv
)

generate_messages(
DEPENDENCIES
std_msgs
Expand Down
28 changes: 28 additions & 0 deletions example/client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#!/usr/bin/env python3
import argparse
import cv_bridge
import cv2
import rospy
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
from detic_ros.srv import DeticSeg
import matplotlib.pyplot as plt

if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument('-image', type=str, help='input image path')
args = parser.parse_args()
image = cv2.imread(args.image)
assert image is not None

rospy.init_node('example_client')
rospy.wait_for_service('/docker/detic_segmentor/segment_image')
image_msg = CvBridge().cv2_to_imgmsg(image, encoding='passthrough')

f = rospy.ServiceProxy('/docker/detic_segmentor/segment_image', DeticSeg)
resp = f(image_msg)
seg_info = resp.seg_info
if resp.debug_image is not None:
image = CvBridge().imgmsg_to_cv2(resp.debug_image)
plt.imshow(image)
plt.show()
2 changes: 2 additions & 0 deletions launch/sample.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<arg name="namespace" default="docker" />

<arg name="verbose" default="true" />
<arg name="enable_pubsub" default="true" />
<arg name="out_debug_img" default="true" />
<arg name="out_debug_segimage" default="true" />
<arg name="confidence_threshold" default="0.5" />
Expand All @@ -26,6 +27,7 @@
output="screen" >
<remap from="~input_image" to="$(arg _input_image)"/>
<param name="verbose" value="$(arg verbose)"/>
<param name="enable_pubsub" value="$(arg enable_pubsub)"/>
<param name="out_debug_img" value="$(arg out_debug_img)"/>
<param name="out_debug_segimage" value="$(arg out_debug_segimage)"/>
<param name="confidence_threshold" value="$(arg confidence_threshold)"/>
Expand Down
25 changes: 20 additions & 5 deletions node_script/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
from rospy import Subscriber, Publisher
from sensor_msgs.msg import Image
from detic_ros.msg import SegmentationInfo
from detic_ros.srv import DeticSeg, DeticSegRequest, DeticSegResponse

from node_config import NodeConfig
from wrapper import DeticWrapper
Expand All @@ -25,20 +26,34 @@ def __init__(self, node_config: Optional[NodeConfig]=None):

# As for large buff_size please see:
# https://answers.ros.org/question/220502/image-subscriber-lag-despite-queue-1/?answer=220505?answer=220505#post-id-22050://answers.ros.org/question/220502/image-subscriber-lag-despite-queue-1/?answer=220505?answer=220505#post-id-220505
self.sub = rospy.Subscriber('~input_image', Image, self.callback, queue_size=1, buff_size=2**24)
self.pub_debug_image = rospy.Publisher('~debug_image', Image, queue_size=1)
self.pub_debug_segmentation_image = rospy.Publisher('~debug_segmentation_image', Image, queue_size=10)
self.pub_info = rospy.Publisher('~segmentation_info', SegmentationInfo, queue_size=1)
self.srv_handler = rospy.Service('~segment_image', DeticSeg, self.callback_srv)

if node_config.enable_pubsub:
self.sub = rospy.Subscriber('~input_image', Image, self.callback_image, queue_size=1, buff_size=2**24)
self.pub_debug_image = rospy.Publisher('~debug_image', Image, queue_size=1)
self.pub_debug_segmentation_image = rospy.Publisher('~debug_segmentation_image', Image, queue_size=10)
self.pub_info = rospy.Publisher('~segmentation_info', SegmentationInfo, queue_size=1)

rospy.loginfo('initialized node')

def callback(self, msg: Image):
def callback_image(self, msg: Image):
seginfo, debug_img, debug_seg_img = self.detic_wrapper.infer(msg)
self.pub_info.publish(seginfo)
if debug_img is not None:
self.pub_debug_image.publish(debug_img)
if debug_seg_img is not None:
self.pub_debug_segmentation_image.publish(debug_seg_img)

def callback_srv(self, req: DeticSegRequest) -> DeticSegResponse:
msg = req.image
seginfo, debug_img, _ = self.detic_wrapper.infer(msg)

resp = DeticSegResponse()
resp.seg_info = seginfo
if debug_img is not None:
resp.debug_image = debug_img
return resp


if __name__=='__main__':
rospy.init_node('detic_node', anonymous=True)
Expand Down
4 changes: 4 additions & 0 deletions node_script/node_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

@dataclass
class NodeConfig:
enable_pubsub: bool
out_debug_img: bool
out_debug_segimage: bool
verbose: bool
Expand All @@ -28,6 +29,7 @@ class NodeConfig:

@classmethod
def from_args(cls,
enable_pubsub: bool = True,
out_debug_img: bool = True,
out_debug_segimage: bool = True,
verbose: bool = False,
Expand All @@ -53,6 +55,7 @@ def from_args(cls,
'Detic_LCOCOI21k_CLIP_SwinB_896b32_4x_ft4x_max-size.pth')

return cls(
enable_pubsub,
out_debug_img,
out_debug_segimage,
verbose,
Expand All @@ -67,6 +70,7 @@ def from_args(cls,
def from_rosparam(cls):

return cls.from_args(
rospy.get_param('~enable_pubsub', True),
rospy.get_param('~out_debug_img', True),
rospy.get_param('~out_debug_segimage', False),
rospy.get_param('~verbose', True),
Expand Down
4 changes: 4 additions & 0 deletions srv/DeticSeg.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
sensor_msgs/Image image
---
detic_ros/SegmentationInfo seg_info
sensor_msgs/Image debug_image

0 comments on commit 29fe219

Please sign in to comment.