5 from geometry_msgs.msg
import Quaternion
6 from amr_interop_msgs.msg
import Location
9 if __name__ ==
"__main__":
10 rospy.init_node(
"fake_location")
12 pub = rospy.Publisher(
"location", Location, queue_size=1)
13 x = rospy.get_param(
"~x", 0.0)
14 y = rospy.get_param(
"~y", 0.0)
15 z = rospy.get_param(
"~z", float(
"nan"))
16 angle_x = rospy.get_param(
"~angle_x", 0.0)
17 angle_y = rospy.get_param(
"~angle_y", 0.0)
18 angle_z = rospy.get_param(
"~angle_z", 0.0)
19 angle_w = rospy.get_param(
"~angle_w", 1.0)
20 publish_rate = rospy.get_param(
"~publish_rate", 1)
21 planar_datum = str(uuid.uuid4())
23 loop_rate = rospy.Rate(publish_rate)
24 location_msg = Location()
25 location_msg.x = float(x)
26 location_msg.y = float(y)
27 location_msg.z = float(z)
28 location_msg.angle.x = float(angle_x)
29 location_msg.angle.y = float(angle_y)
30 location_msg.angle.z = float(angle_z)
31 location_msg.angle.w = float(angle_w)
32 location_msg.planar_datum = planar_datum
33 while not rospy.is_shutdown():
34 pub.publish(location_msg)