successfully published rgb image
This commit is contained in:
parent
5deca92c83
commit
f36934292b
@ -323,6 +323,8 @@ class CameraPlugin(Plugin):
|
|||||||
self.info_pub = rospy.Publisher(topic, CameraInfo, queue_size=10)
|
self.info_pub = rospy.Publisher(topic, CameraInfo, queue_size=10)
|
||||||
topic = self.name + "/depth/image_rect_raw"
|
topic = self.name + "/depth/image_rect_raw"
|
||||||
self.depth_pub = rospy.Publisher(topic, Image, queue_size=10)
|
self.depth_pub = rospy.Publisher(topic, Image, queue_size=10)
|
||||||
|
topic = self.name + "/color/image_rect_raw"
|
||||||
|
self.rgb_pub = rospy.Publisher(topic, Image, queue_size=10)
|
||||||
|
|
||||||
def update(self):
|
def update(self):
|
||||||
stamp = rospy.Time.now()
|
stamp = rospy.Time.now()
|
||||||
@ -332,7 +334,7 @@ class CameraPlugin(Plugin):
|
|||||||
msg.header.stamp = stamp
|
msg.header.stamp = stamp
|
||||||
self.info_pub.publish(msg)
|
self.info_pub.publish(msg)
|
||||||
|
|
||||||
_, depth, _ = self.camera.get_image()
|
color, depth, mask = self.camera.get_image()
|
||||||
|
|
||||||
if self.cam_noise:
|
if self.cam_noise:
|
||||||
depth = apply_noise(depth)
|
depth = apply_noise(depth)
|
||||||
@ -341,6 +343,10 @@ class CameraPlugin(Plugin):
|
|||||||
msg.header.stamp = stamp
|
msg.header.stamp = stamp
|
||||||
self.depth_pub.publish(msg)
|
self.depth_pub.publish(msg)
|
||||||
|
|
||||||
|
msg = self.cv_bridge.cv2_to_imgmsg((color).astype(np.uint8), encoding='rgb8')
|
||||||
|
msg.header.stamp = stamp
|
||||||
|
self.rgb_pub.publish(msg)
|
||||||
|
|
||||||
|
|
||||||
class MockActionsPlugin(Plugin):
|
class MockActionsPlugin(Plugin):
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
|
Loading…
x
Reference in New Issue
Block a user