From 86baf6b729485a544cc9e928048193c5db9071dc Mon Sep 17 00:00:00 2001
From: Anton Tetov <anton@tetov.se>
Date: Wed, 8 Sep 2021 18:49:40 +0200
Subject: [PATCH] adapted to ilon_car_ctrl

---
 .gitignore                     |  1 +
 nodes/mecanum_drive_controller | 16 ++++++++++------
 package.xml                    |  2 ++
 3 files changed, 13 insertions(+), 6 deletions(-)

diff --git a/.gitignore b/.gitignore
index 0d20b64..f4f1641 100755
--- a/.gitignore
+++ b/.gitignore
@@ -1 +1,2 @@
 *.pyc
+.vscode/
diff --git a/nodes/mecanum_drive_controller b/nodes/mecanum_drive_controller
index 9ff7d57..baec0a7 100755
--- a/nodes/mecanum_drive_controller
+++ b/nodes/mecanum_drive_controller
@@ -3,22 +3,23 @@ from __future__ import division
 
 import rospy
 from geometry_msgs.msg import Twist
-from std_msgs.msg import Int16MultiArray
+from ilon_wheel_ctrl.msg import WheelRates
 
 from mecanum_drive import controller
 
 class ControllerNode:
+    ZERO_RATES = WheelRates(frontLeft=0, frontRight=0, backLeft=0, backRight=0)
 
     def __init__(self):
         self.controller = controller.Controller()
         self.linearXVelocity = 0.0
         self.linearYVelocity = 0.0
         self.angularVelocity = 0.0
-        self.wheels_to_send = Int16MultiArray()
+        self.wheels_to_send = WheelRates()
 
     def main(self):                                        
         self.wheelPub = rospy.Publisher('wheels_desired_rate',
-                                        Int16MultiArray, queue_size=1)
+                                        WheelRates, queue_size=1)
                                         
         rospy.init_node('mecanum_drive_controller')
         self.nodeName = rospy.get_name()
@@ -49,11 +50,14 @@ class ControllerNode:
             speeds = self.controller.getSpeeds(self.linearXVelocity,self.linearYVelocity,
                                                self.angularVelocity)
 
-            self.wheels_to_send.data = [int(speeds.frontLeft), int(speeds.frontRight), int(speeds.rearLeft), int(speeds.rearRight)]
+            self.wheels_to_send.frontLeft = int(speeds.frontLeft)
+            self.wheels_to_send.frontRight = int(speeds.frontRight)
+            self.wheels_to_send.backLeft = int(speeds.rearLeft)
+            self.wheels_to_send.backRight = int(speeds.rearRight)
+
             self.wheelPub.publish(self.wheels_to_send)
         else:
-            self.wheels_to_send.data = [0, 0, 0, 0]
-            self.wheelPub.publish(self.wheels_to_send)
+            self.wheelPub.publish(self.ZERO_RATES)
 
     def twistCallback(self, twist):
         self.linearXVelocity = twist.linear.x
diff --git a/package.xml b/package.xml
index eb225cf..4f0467a 100755
--- a/package.xml
+++ b/package.xml
@@ -17,6 +17,8 @@
   <depend>geometry_msgs</depend>
   <depend>actionlib_msgs</depend>
   <build_depend>rostest</build_depend>
+  <build_depend>ilon_wheel_cmd</build_depend>
   <depend>message_generation</depend>
+  <exec_depend>ilon_wheel_cmd</exec_depend>
   
 </package>
-- 
GitLab