set_pinger_position.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 # Copyright 2018 Joanthan Wheare
3 #
4 # Licensed under the Apache License, Version 2.0 (the "License");
5 # you may not use this file except in compliance with the License.
6 # You may obtain a copy of the License at
7 #
8 # http://www.apache.org/licenses/LICENSE-2.0
9 #
10 # Unless required by applicable law or agreed to in writing, software
11 # distributed under the License is distributed on an "AS IS" BASIS,
12 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 # See the License for the specific language governing permissions and
14 # limitations under the License.
15 
16 import random
17 import rospy
18 
19 from geometry_msgs.msg import Vector3
20 from usv_msgs.msg import RangeBearing
21 from visualization_msgs.msg import Marker
22 
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.
32 """
33 
34 
36  """Class used to store the parameters and variables for the script.
37  """
38  def __init__(self):
39  """Initialise and run the class."""
40  rospy.init_node("set_pinger_position")
41 
42  # Load the positions of the pingers.
43  self.pingerPositions = list()
44  i = 1
45  while rospy.has_param('~position_' + str(i)):
46  self.pingerPositions.append(rospy.get_param('~position_' + str(i)))
47  i = i + 1
48 
49  # If there are no matching positions, initialise to the origin.
50  if i == 1:
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)
56 
57  while not rospy.is_shutdown():
58 
59  # Choose a position for the pinger.
60  position = random.choice(self.pingerPositions)
61 
62  # Create a vector message.
63  msg = Vector3()
64  msg.x = position[0]
65  msg.y = position[1]
66  msg.z = position[2]
67  self.pingerPub.publish(msg)
68 
69  msg = Marker()
70  msg.header.frame_id = "/map"
71  msg.header.stamp = rospy.get_rostime()
72  msg.ns = ""
73  msg.id = 0
74  msg.type = Marker.SPHERE
75  msg.action = Marker.ADD
76 
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
84 
85  msg.scale.x = 1.0
86  msg.scale.y = 1.0
87  msg.scale.z = 1.0
88 
89  msg.color.r = 1.0
90  msg.color.g = 0.0
91  msg.color.b = 0.0
92  msg.color.a = 1.0
93 
94  self.markerPub.publish(msg)
95 
96  # Change position every 10 seconds.
97  rospy.sleep(10.)
98 
99 
100 if __name__ == '__main__':
101  pinger = PingerPosition()


vrx_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:56