19 from geometry_msgs.msg
import Vector3
20 from usv_msgs.msg
import RangeBearing
21 from visualization_msgs.msg
import Marker
23 """@package set_pinger_position.py 24 Automatically generate a position for a simulated USV pinger. This 25 position is published both as a Vector3 to the plugin, and as a Marker that 26 can be visualised. This visualisation can be used as a ground truth to 27 compare with the estimated pinger position. 28 Possible positions are stored as ROS parameters. The node assumes that 29 positions will be three element vectors each stored in the nodes parameter 30 space in the format position_n starting with position_1. If no positions 31 are available, the node will default to the origin. 36 """Class used to store the parameters and variables for the script. 39 """Initialise and run the class.""" 40 rospy.init_node(
"set_pinger_position")
45 while rospy.has_param(
'~position_' + str(i)):
46 self.pingerPositions.append(rospy.get_param(
'~position_' + str(i)))
51 self.pingerPositions.append([0, 0, 0])
52 self.
pingerPub = rospy.Publisher(
"/wamv/sensors/pingers/pinger/set_pinger_position",
53 Vector3, queue_size=10, latch=
True)
54 self.
markerPub = rospy.Publisher(
"/wamv/sensors/pingers/pinger/marker/ground_truth", Marker,
55 queue_size=10, latch=
True)
57 while not rospy.is_shutdown():
67 self.pingerPub.publish(msg)
70 msg.header.frame_id =
"/map" 71 msg.header.stamp = rospy.get_rostime()
74 msg.type = Marker.SPHERE
75 msg.action = Marker.ADD
77 msg.pose.position.x = position[0]
78 msg.pose.position.y = position[1]
79 msg.pose.position.z = position[2]
80 msg.pose.orientation.x = 0.0
81 msg.pose.orientation.y = 0.0
82 msg.pose.orientation.z = 0.0
83 msg.pose.orientation.w = 1.0
94 self.markerPub.publish(msg)
100 if __name__ ==
'__main__':