Skip to content

Commit

Permalink
(color_extractor) Create a node listener and call service (#228)
Browse files Browse the repository at this point in the history
* Create a node listener and call service

* Edit node name

* Make class for service client

* Add executable script

* Add service argument and start subscriber after client

* Add rospy argument filter
  • Loading branch information
GustavoDCC committed May 5, 2024
1 parent ecc0a87 commit d91bc5a
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 0 deletions.
1 change: 1 addition & 0 deletions image_recognition_color_extractor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ catkin_package()
install(PROGRAMS
scripts/color_extractor_node
scripts/get_colors
scripts/get_colors_stream
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand Down
35 changes: 35 additions & 0 deletions image_recognition_color_extractor/scripts/get_colors_stream
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
#!/usr/bin/env python
import argparse

import rospy

from sensor_msgs.msg import Image

from image_recognition_msgs.srv import Recognize

class ExtractColorClient:
def __init__(self, image_topic, color_service):
self.color_proxy = rospy.ServiceProxy(color_service, Recognize)
self.color_proxy.wait_for_service(timeout=20)

# Subscriber will start immediately
self.image_sub = rospy.Subscriber(image_topic, Image, self.color_callback)

def color_callback(self, msg):
# Simply print out values in our custom message.
colors = self.color_proxy(msg)
rospy.loginfo(colors)

if __name__ == '__main__':

myargs = rospy.myargv()
parser = argparse.ArgumentParser(description='Get dominant colors from image')
parser.add_argument('--topic', required=False, default='/image', type=str, help='Topic')
parser.add_argument('--service', required=False, default='extract_color', type=str, help='Service')
args = parser.parse_args(myargs[1:])

rospy.init_node('color_extractor_stream')

extract_color_client = ExtractColorClient(args.topic, args.service)

rospy.spin()

0 comments on commit d91bc5a

Please sign in to comment.