From 6741b49f572958d73b51c15b7761c554995ab1e2 Mon Sep 17 00:00:00 2001 From: Paul-Winpenny <92634321+Paul-Winpenny@users.noreply.github.com> Date: Wed, 18 Dec 2024 13:39:15 +0000 Subject: [PATCH] Changed topic to just different one for start node in call mode . --- App/RobobinApp/Views/MainPage.xaml.cs | 5 +++++ App/RobobinApp/Views/MainPage_Android.xaml.cs | 5 +++++ ros2/src/robobin/robobin/uwb_navigation_node.py | 7 ++++--- ros2/src/robobin/robobin/uwb_pathing_node.py | 2 +- 4 files changed, 15 insertions(+), 4 deletions(-) diff --git a/App/RobobinApp/Views/MainPage.xaml.cs b/App/RobobinApp/Views/MainPage.xaml.cs index 0f7f925b..533e36ad 100644 --- a/App/RobobinApp/Views/MainPage.xaml.cs +++ b/App/RobobinApp/Views/MainPage.xaml.cs @@ -52,6 +52,11 @@ namespace RobobinApp.Views private void OnGraphicsViewTapped(object sender, TappedEventArgs e) { + if (App.WifiManager.Mode != "Call") + { + DisplayAlert("NO CALL","Bin must be in call mode to use this feature!","Sorry!"); + return; + } var tapPoint = e.GetPosition(GraphicsView); var drawable = (GraphicsDrawable)Resources["drawable"]; diff --git a/App/RobobinApp/Views/MainPage_Android.xaml.cs b/App/RobobinApp/Views/MainPage_Android.xaml.cs index 99c1a14f..f7059f40 100644 --- a/App/RobobinApp/Views/MainPage_Android.xaml.cs +++ b/App/RobobinApp/Views/MainPage_Android.xaml.cs @@ -26,6 +26,11 @@ namespace RobobinApp.Views private void OnGraphicsViewTapped(object sender, TappedEventArgs e) { + if (App.WifiManager.Mode != "Call") + { + DisplayAlert("NO CALL", "Bin must be in call mode to use this feature!", "Sorry!"); + return; + } var tapPoint = e.GetPosition(GraphicsView); var drawable = (GraphicsDrawable)Resources["drawable"]; diff --git a/ros2/src/robobin/robobin/uwb_navigation_node.py b/ros2/src/robobin/robobin/uwb_navigation_node.py index 5972d856..56ff5210 100644 --- a/ros2/src/robobin/robobin/uwb_navigation_node.py +++ b/ros2/src/robobin/robobin/uwb_navigation_node.py @@ -66,6 +66,7 @@ class UWBNode(Node): super().__init__('uwb_navigation_node') self.publisher = self.create_publisher(Point, '/tag1_location', 10) + self.start_publisher = self.create_publisher(Point, '/start_location', 10) self.target_location_pub = self.create_publisher(Point, '/target_location', 10) self.api_pub = self.create_publisher(String, '/api_command', 10) @@ -167,9 +168,9 @@ class UWBNode(Node): # Extract yaw from quaternion using transforms3d orientation_q = msg.orientation orientation_list = [orientation_q.w, orientation_q.x, orientation_q.y, orientation_q.z] - roll, pitch, yaw = quat2euler(orientation_list) # Converts quaternion to Euler angles + # roll, pitch, yaw = quat2euler(orientation_list) # Converts quaternion to Euler angles - self.current_yaw = yaw # Update current yaw + self.current_yaw = 0 # Update current yaw # self.get_logger().info(f"IMU Yaw: {yaw:.2f} radians") def determine_anchor_coords(self, measured_distances): @@ -304,7 +305,7 @@ class UWBNode(Node): # Publish current position position_msg = Point(x=self.current_tag1_position[0], y=self.current_tag1_position[1], z=0.0) - self.publisher.publish(position_msg) + self.start_publisher.publish(position_msg) # Publish target position target_msg = Point(x=target_pos[0], y=target_pos[1], z=0.0) diff --git a/ros2/src/robobin/robobin/uwb_pathing_node.py b/ros2/src/robobin/robobin/uwb_pathing_node.py index 6c432442..dec8b955 100644 --- a/ros2/src/robobin/robobin/uwb_pathing_node.py +++ b/ros2/src/robobin/robobin/uwb_pathing_node.py @@ -13,7 +13,7 @@ class UWBPathingNode(Node): self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10) # Subscriptions - self.create_subscription(Point, '/tag1_location', self.current_location_callback, 10) + self.create_subscription(Point, '/start_location', self.current_location_callback, 10) self.create_subscription(Point, '/target_location', self.target_location_callback, 10) # Current and target positions -- GitLab