Go to the documentation of this file.00001
00002 '''
00003 Created on Feb 04, 2013
00004
00005 @author: dnad
00006 '''
00007 import rospy;
00008 from geometry_msgs.msg import PointStamped;
00009 from visualization_msgs.msg import Marker;
00010
00011 def onPoint(data):
00012 marker = Marker();
00013 marker.header.frame_id = "/cart2/local";
00014 marker.header.stamp = rospy.Time();
00015 marker.ns = "cart2";
00016 marker.id = 0;
00017 marker.type = Marker.SPHERE;
00018 marker.action = Marker.MODIFY;
00019 marker.pose.position.x = data.point.x;
00020 marker.pose.position.y = data.point.y;
00021 marker.pose.position.z = data.point.z;
00022 marker.pose.orientation.w = 1.0;
00023
00024 marker.scale.x = 0.3;
00025 marker.scale.y = 0.3;
00026 marker.scale.z = 0.3;
00027 marker.color.a = 1.0;
00028 marker.color.r = 0.0;
00029 marker.color.g = 1.0;
00030 marker.color.b = 0.0;
00031 vis_pub.publish(marker);
00032
00033 if __name__ == "__main__":
00034 rospy.init_node("cart2_rviz");
00035
00036 rospy.Subscriber("target_point", PointStamped, onPoint)
00037 vis_pub = rospy.Publisher("visualization_marker",Marker)
00038
00039 while not rospy.is_shutdown():
00040 rospy.spin();
00041
00042
00043