Skip to content
Snippets Groups Projects
Commit 8e7f54f5 authored by Emil Harlan's avatar Emil Harlan
Browse files

a

parent 20e0f0d2
No related branches found
No related tags found
No related merge requests found
...@@ -14,16 +14,8 @@ import os ...@@ -14,16 +14,8 @@ import os
import socket import socket
import ping3 import ping3
class vel_from_ros_node(Node): class vel_from_ros_node(Node):
def __init__(self, my_ep_chassis): def __init__(self, my_ep_chassis):
super().__init__("vel_from_ros") super().__init__("vel_from_ros")
self.response = False self.response = False
self.timer = threading.Timer(1, self.check_connection) self.timer = threading.Timer(1, self.check_connection)
...@@ -31,32 +23,31 @@ class vel_from_ros_node(Node): ...@@ -31,32 +23,31 @@ class vel_from_ros_node(Node):
self.my_ep_chassis = my_ep_chassis self.my_ep_chassis = my_ep_chassis
self.get_vel_from_ros_ = self.create_subscription(Twist, "/cmd_vel", self.pose_callback, 10) self.get_vel_from_ros_ = self.create_subscription(Twist, "/cmd_vel", self.pose_callback, 10)
def check_connection(self): def check_connection(self):
self.response = self.check_ip_reachability() if self.isConnected():
if(self.response != True): self.response = True
self.my_ep_chassis.drive_speed(x = 0, y = 0, z = 0.5) else:
self.response = False
self.my_ep_chassis.drive_speed(x=0, y=0, z=0.5)
self.timer = threading.Timer(1, self.check_connection)
self.timer.start()
def check_ip_reachability(self): def isConnected(self):
response = ping3.ping("192.168.1.77") response = ping3.ping("192.168.1.77")
if response is not None: if response is not None:
return True return True
else: else:
return False return False
def pose_callback(self, msg: Twist): def pose_callback(self, msg: Twist):
print("kek") if self.response:
if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0)):
self.my_ep_chassis.drive_speed(x=0, y=0, z=0.5)
if((msg.angular.z == 0.0 and msg.linear.x == 0.0 and msg.linear.y == 0.0) or self.response != True): else:
self.my_ep_chassis.drive_speed(x = 0, y = 0, z = 0.5) self.my_ep_chassis.drive_speed(x=msg.linear.x, y=-msg.linear.y, z=-msg.angular.z * (180 / math.pi))
else: else:
self.my_ep_chassis.drive_speed(x = msg.linear.x, y = -msg.linear.y, z = -msg.angular.z * (180 / math.pi)) self.my_ep_chassis.drive_speed(x=0, y=0, z=0.5)
def main(): def main():
ep_robot = robot.Robot() ep_robot = robot.Robot()
...@@ -70,4 +61,6 @@ def main(): ...@@ -70,4 +61,6 @@ def main():
rclpy.shutdown() rclpy.shutdown()
ep_robot.close() ep_robot.close()
\ No newline at end of file if __name__ == '__main__':
main()
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment