From 16d36322dc3c3306d08a20401ed3a455198d846e Mon Sep 17 00:00:00 2001 From: Daniel Christoph <daniel.christoph@informatik.hu-berlin.de> Date: Sat, 4 Jan 2020 23:20:02 +0100 Subject: [PATCH] Update Simulation/location_monitor/scripts/location_monitor_node.py --- .../scripts/location_monitor_node.py | 69 +++++++++++++++++++ 1 file changed, 69 insertions(+) create mode 100644 Simulation/location_monitor/scripts/location_monitor_node.py diff --git a/Simulation/location_monitor/scripts/location_monitor_node.py b/Simulation/location_monitor/scripts/location_monitor_node.py new file mode 100644 index 0000000..bb4a6cf --- /dev/null +++ b/Simulation/location_monitor/scripts/location_monitor_node.py @@ -0,0 +1,69 @@ +#!/usr/bin/env python + +import math +import rospy +from nav_msgs.msg import Odometry +from gazebo_msgs.srv import GetModelState + + +botx = 0 +boty = 0 + +class Block: + def __init__(self, name, relative_entity_name): + self._name = name + self._relative_entity_name = relative_entity_name + + +class Tutorial: + + _blockListDict = { + 'block_a': Block('ball' , 'link'), + } + + def show_gazebo_models(self): + + try: + model_coordinates = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState) + for block in self._blockListDict.itervalues(): + blockName = str(block._name) + resp_coordinates = model_coordinates(blockName, block._relative_entity_name) + l_x = resp_coordinates.pose.position.x + l_y = resp_coordinates.pose.position.y + dist = distance(botx, boty, l_x, l_y) + print(dist) + if dist < 0.20: + rospy.loginfo("Collision!") + + + print(blockName) + print("X: " + str(l_x)) + print("Y: " + str(l_y)) + dist = 0 + + except rospy.ServiceException as e: + rospy.loginfo("Get Model State service call failed: {0}".format(e)) + + +def distance(x1, y1, x2, y2): + dist = math.sqrt((x2 - x1)**2 + (y2 - y1)**2) + return dist + + +def callback(msg): + botx = msg.pose.pose.position.x + boty = msg.pose.pose.position.y + print("BotX: " + str(botx)) + print("BotY: " + str(boty)) + tuto = Tutorial() + tuto.show_gazebo_models() + + + +def main(): + rospy.init_node('location_monitor') + rospy.Subscriber("/odom", Odometry, callback) + rospy.spin() + +if __name__ == '__main__': + main() -- GitLab