Go to the documentation of this file.00001
00002
00003
00004
00005 import rospy
00006 from mongodb_store.message_store import MessageStoreProxy
00007 from posedetection_msgs.msg import Object6DPose
00008 from visualization_msgs.msg import MarkerArray
00009 from geometry_msgs.msg import TransformStamped
00010 from datetime import datetime, timedelta
00011 import tf
00012
00013 from transform_utils import TransformationUtils as T
00014 from visualization_utils import VisualizationUtils as V
00015
00016 class DBPlay(object):
00017 def __init__(self):
00018 self.db_name = rospy.get_param('~db_name','jsk_robot_lifelog')
00019 self.col_name = rospy.get_param('~col_name', 'pr1012')
00020 self.use_ros_time = rospy.get_param('~use_ros_time', True)
00021 self.use_sim_time = rospy.get_param('use_sim_time', False)
00022 self.downsample = rospy.get_param("~downsample", 3)
00023 self.label_downsample = rospy.get_param("~label_downsample", 10)
00024 self.duration = rospy.get_param('~duration', 10)
00025 self.msg_store = MessageStoreProxy(database=self.db_name,
00026 collection=self.col_name)
00027 rospy.loginfo("connected to %s.%s" % (self.db_name, self.col_name))
00028 self.pub = rospy.Publisher('/move_base_marker_array', MarkerArray)
00029 self.marker_count = 0
00030
00031 def run(self):
00032 while not rospy.is_shutdown():
00033 rospy.logdebug("$gt: %d" % (rospy.Time.now().secs - self.duration * 60 * 60 * 24))
00034 if self.use_ros_time or self.use_sim_time:
00035 trans = self.msg_store.query(type=TransformStamped._type,
00036 message_query={"header.stamp.secs": {
00037 "$lte": rospy.Time.now().secs,
00038 "$gt": rospy.Time.now().secs - self.duration * 60 * 60 * 24
00039 }},
00040 sort_query=[("$natural", 1)])
00041 else:
00042 trans = self.msg_store.query(type=TransformStamped._type,
00043 meta_query={"inserted_at": {
00044 "$gt": datetime.utcnow() - timedelta(days=self.duration)
00045 }},
00046 sort_query=[("$natural", 1)])
00047 rospy.loginfo("found %d msgs" % len(trans))
00048 m_arr = MarkerArray()
00049 m_arr.markers = V.transformStampedArrayToLabeledLineStripMarker(trans[::self.downsample], label_downsample=self.label_downsample, discrete=True)
00050 m_arr.markers = V.transformStampedArrayToLabeledArrayMarker(trans[::self.downsample], label_downsample=self.label_downsample, discrete=True)
00051 self.pub.publish(m_arr)
00052 rospy.sleep(1.0)
00053 rospy.loginfo("publishing move_base_marker_array")
00054
00055
00056 if __name__ == '__main__':
00057 rospy.init_node('visualize_move_base')
00058 o = DBPlay()
00059 o.run()