11 from __future__
import print_function
18 import tensorflow
as tf
21 import netvlad_tf.net_from_mat
as nfm
22 import netvlad_tf.nets
as nets
24 from std_msgs.msg
import String
25 from sensor_msgs.msg
import Image
26 from cv_bridge
import CvBridge, CvBridgeError
27 from rtabmap_ros
import compression
as cp
28 from rtabmap_ros.msg
import GlobalDescriptor
34 self.
dim = rospy.get_param(
'~dim', 4096)
35 self.
scale = rospy.get_param(
'~scale', 1.0)
36 rospy.loginfo(
"Parameter dim=%d", self.
dim)
37 rospy.loginfo(
"Parameter scale=%d", self.
scale)
39 tf.reset_default_graph()
42 dtype=tf.float32, shape=[
None,
None,
None, 3])
48 self.
saver.restore(self.
sess, nets.defaultCheckpoint())
50 self.
pub = rospy.Publisher(
'netvlad_descriptor', GlobalDescriptor, queue_size=1)
58 cv_image = self.
bridge.imgmsg_to_cv2(data,
"rgb8")
59 except CvBridgeError
as e:
63 width = int(cv_image.shape[1] * self.
scale)
64 height = int(cv_image.shape[0] * self.
scale)
65 cv_image = cv2.resize(cv_image, (width, height), interpolation = cv2.INTER_AREA)
67 batch = np.expand_dims(cv_image, axis=0)
69 result = result[:,:self.
dim]
71 descriptor = GlobalDescriptor()
73 descriptor.header = data.header
74 descriptor.data = cp.compress(result)
75 self.
pub.publish(descriptor)
77 rospy.loginfo(
"Extracting descriptor (img=%dx%d, dim=%d): %fs", cv_image.shape[1], cv_image.shape[0], self.
dim, end-start)
80 rospy.init_node(
'netvlad', anonymous=
True)
84 except KeyboardInterrupt:
85 print(
"Shutting down")
87 if __name__ ==
'__main__':