User Tools

Site Tools


nxt_automation_alternative_practical_implementations

NXT Automation Alternatives & Practical Implementations
Author: Hashim H., Email: hameeh1@unlv.nevada.edu
Date: Last modified on [11/23/24]
Keywords: NXT, Teleoperation, Automation

Motivation and Audience

This page serves to document the practical applications of NXT automation as outlined by the "NXT Automation Implementation" tutorial. This includes alternative means of communication which would not be primarily utilized for the original tutorial. Though certain avenues remain incomplete, the foundation found herein may be assistive in furthering such or even be applied to unrelated projects. This information assumes:

  • BricxCC (Bricx Command Center) application setup
  • A basic understanding of C+ + (or general object oriented programming)
  • Familiarity with OpenCV

Parts List and Sources

Software

Arduino-I2C Alternative

The I2C communication protocol is the means through which LEGO NXT peripherals are able to communicate with the module, meaning that responses may be programmed in correspondence with particular inputs from a microcontroller. An arduino uno has been used for this example.

Setup

Step 1 [Theory/Reading]

Prior to implementation, it is important to understand the means through which the I2C protocol operates. The following documents will be greatly assistive outside of the scope of this tutorial:

I2C is a communication protocol combining feature of SPI and UARTs. Multiple slaves are able to connect to a master unit, or even multiple masters. Serial Data (SDA) and Serial Clock (SCL) are lines for data transmission and the clock signal respectively, with bit output being synchronized to the sampling of bits by the clock which is controlled by the master.

I2C uses “messages” broken up into frames:

  • Starting condition (SDA switches from high to low voltage before SCL switches from high to low)
  • Address frame (slave's binary address [7-10 bits])
  • Data frame(s) with acknowledgement sent in between
  • Stopping condition (Inversion of starting [low to high])

Acknowledge bits are returned to the sender from the receiving device if an address or data frame is successfully received.

The read/write bit at the end of the address frame determines whether data is being sent to or received from the master.

Step 2 [Hardware Setup]

In order to communicate via I2C, a standard NXT connector wire may be stripped down to the individual wires it is comprised of, with each of the wires being correspondent to a particular functionality as detailed in the reading provided. Solder on connector pins to the utilized wires, after which point the NXT may be plugged directly from port 1 into the arduino uno.

Alternatives exist in the form of breakout boards and shields, though the latter may be limited to a certain number of motors in some cases and will requires research and implementation outside the scope of this tutorial.

Programming

The most consistent means of I2C communication encountered due to both ease of abstraction and time dedicated to troubleshooting utilizes the RobotC IDE rather than BricxCC. It is certainly possible and indeed recommended to utilize the latter considering the limited license of the former, though code for RobotC is documented to provide guidance:

robotC_I2C.c
  1. #pragma config(Sensor, S1,TIR,sensorI2CCustom)
  2.  
  3. // Define the Arduino Address
  4. // Address is 0x0A on the Arduino: (Binary) 1010
  5. // Bit shifted out with one 0: (Binary) 10100 = 0x14
  6. #define ARDUINO_ADDRESS 0x14
  7. #define ARDUINO_PORT S1
  8.  
  9. ubyte I2Cmessage[22];
  10. char I2Creply[20];
  11.  
  12. void i2c_read_registers_text(ubyte register_2_read, int message_size, int return_size){
  13. memset(I2Creply, 0, sizeof(I2Creply));
  14. message_size = message_size+3;
  15.  
  16. I2Cmessage[0] = message_size; // Messsage Size
  17. I2Cmessage[1] = ARDUINO_ADDRESS;
  18. I2Cmessage[2] = register_2_read; // Register
  19. sendI2CMsg(S1, &I2Cmessage[0], return_size);
  20. wait1Msec(20);
  21.  
  22. readI2CReply(ARDUINO_PORT, &I2Creply[0], return_size);
  23.  
  24. int i = 0;
  25. while(true){
  26. writeDebugStream("%c", I2Creply[i]);
  27. i++;
  28. if(I2Creply[i] == 0) break;
  29. }
  30. writeDebugStreamLine(" ");
  31. }
  32.  
  33. task main()
  34. {
  35. while(true){
  36. // i2c_write_registers(0x01, 0x01, 0x00, 0x0A, 0, 0, 0);
  37. i2c_read_registers_text(0x01, 0, 10);
  38. motor[motorB] = I2Creply[0];
  39. i2c_read_registers_text(0x02, 0, 10);
  40. motor[motorC] = -I2Creply[0];
  41. }
  42.  
  43. }

Teensy-PS2 Alternative [*Dubious Functionality]

This alternative sees direct connection of a PS2 receiver module to a Teensy microcontroller so as to send signals corresponding to particular inputs. It must be noted that this alternative in its current state has not been followed through on completely, but is documented considering its potential to function if a greater deal deal of time dedicated.

Setup

Step 1 [Theory/Reading]

Prior to any form of implementation, it is best to understand the Playstation2's controller communication protocol to some extent. The following webpages document the protocol (mostly reception rather than transmission) and practical examples of utilization therein:

Step 2 [Hardware Setup]

As detailed in the practical examples listed, a Playstation2 wired controller (in this case wireless receiver) may be stripped and its wires soldered particular pins on the Teensy 2.0 microcontroller. It is important to note that there are instances wherein aftermarket controllers may not hold the same colors as listed in either tutorial, and so connections must be checked relative to the pinouts contained within the given tutorials.

Step 3 [Teensy Setup]

Following soldering, the Teensy 2.0 must be connected to compute unit with the Teensy Loader installed in order to load programs onto the microcontroller. It is recommended that you start off with an existing hex file from either of the practical examples listed to troubleshoot and verify connections. If at no point an attached motor spins on a properly powered NXT with correspondent programming loaded, it may be best to use a multimeter to test connectivity or double check every wire is connected to the correct PS2 pinout.

Programming

Though it is recommended that you attempt to work of the files from the existing projects listed above, the following is a code example able to spin a motor at a consistent rate, but cannot be updated in real time, likely due to timing issues:

Additional Scripts

Following is a python script intended to inform motor speed in a manner built off a more primitive finite case version of the "NXT Automation Implementation" tutorial using visual data with the OpenCV computer vision library:

nxt_basic_vision.py
  1. #import necessary packages
  2. import numpy as np
  3. import cv2
  4. import serial
  5. import time
  6.  
  7. #set constant variables
  8. ball_detected = False
  9. video = cv2.VideoCapture(1)
  10. width = 960
  11. height = 540
  12. num = "3"
  13. positionX = 0
  14.  
  15. #intialize microcontroller serial communication
  16. arduino = serial.Serial(port='COM12', baudrate=115200, timeout=.1)
  17.  
  18. #function defining serial communication
  19. def write_read(x):
  20. arduino.write(bytes(x, 'utf-8'))
  21. time.sleep(0.05)
  22. data = arduino.readline()
  23. return data
  24.  
  25. #program loop
  26. while True:
  27. (grabbed, frame) = video.read()
  28. if not grabbed:
  29. break
  30.  
  31. frame = cv2.resize(frame, (width, height))
  32.  
  33. #apply blur to average local values and use HSV for color detection [red]
  34. blur = cv2.GaussianBlur(frame, (21, 21), 0)
  35. hsv = cv2.cvtColor(blur, cv2.COLOR_BGR2HSV)
  36.  
  37. lower = [149, 163, 150]
  38. upper = [255, 255, 255]
  39. lower = np.array(lower, dtype="uint8")
  40. upper = np.array(upper, dtype="uint8")
  41.  
  42. mask = cv2.inRange(hsv, lower, upper)
  43.  
  44. #outline detected color/object with circular contour
  45. contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
  46.  
  47. detections = []
  48. for cnt in contours:
  49. area = cv2.contourArea(cnt)
  50. if area > 100:
  51. (x, y), radius = cv2.minEnclosingCircle(cnt)
  52. center = (int(x), int(y))
  53. radius = int(radius)
  54. positionX = x
  55. cv2.circle(frame, center, radius, (0,255,0), 2)
  56.  
  57. #create visual mask and count number of pixels in mask
  58. output = cv2.bitwise_and(frame, hsv, mask=mask)
  59.  
  60. no_red = cv2.countNonZero(mask)
  61. print(no_red)
  62.  
  63. #send serial messages based on number of pixels detected
  64. if int(no_red) > 1000:
  65. ball_detected = True
  66. else:
  67. ball_detected = False
  68.  
  69. cv2.imshow("output", output)
  70.  
  71. if ball_detected:
  72. if positionX < (width/2)-40:
  73. num = "3"
  74. elif positionX > (width/2)+40:
  75. num = "4"
  76. else:
  77. if int(no_red) < 45250:
  78. num = "1"
  79. else:
  80. num = "2"
  81. write_read(num)
  82. time.sleep(1)
  83. num = "5"
  84.  
  85. write_read(num)
  86. else:
  87. value = write_read("3")
  88.  
  89. #close program
  90. if cv2.waitKey(1) & 0xFF == ord('q'):
  91. break
  92.  
  93. cv2.destroyAllWindows()
  94. video.release()

Motion capture data would be the primary means of informing motor speed in practice of the project's development. The following is a ROSPY based script utilizing motion capture data alongside a PID controller to hone a bearing angle relative to a ball and move toward the ball in question when this bearing angle is matched:

nxt_mocap.py
  1. #!/usr/bin/env python
  2. #importing necessary classes
  3. import rospy
  4. from nav_msgs.msg import Odometry
  5. from geometry_msgs.msg import TransformStamped
  6. import serial
  7. import time
  8. import math
  9. from scipy.interpolate import interp1d
  10.  
  11. #instantiate both dynamic and constant variables
  12. roll = pitch = yaw = 0.0
  13. Pi = math.pi
  14. radToDegMult = 180/Pi
  15.  
  16. xTransformCar = 0.0
  17. yTransformCar = 0.0
  18.  
  19. xTransformBall = 0.0
  20. yTransformBall = 0.0
  21.  
  22. angleRelativeDeg = 0.0
  23.  
  24. speed = 0
  25.  
  26. angleRangeConst = 3.2
  27. mapConst = 1.2
  28. dt = 0
  29.  
  30. lowBound = 15
  31. highBound = 60
  32.  
  33. newLine = "/n"
  34.  
  35. #initialize serial communication with microcontroller
  36. arduino = serial.Serial(port='/dev/ttyUSB0', baudrate=115200, timeout=.1)
  37.  
  38. #instantiate publishers for both "car" (mobile robot) and ball
  39. carPub = rospy.Publisher('car_transform_data', TransformStamped, queue_size = 10)
  40. ballPub = rospy.Publisher('ball_transform_data', TransformStamped, queue_size = 10)
  41.  
  42. #PID class definition
  43. class PID:
  44. def __init__(self, Kp, Ki, Kd):
  45. self.Kp = Kp
  46. self.Ki = Ki
  47. self.Kd = Kd
  48. self.last_error = 0
  49. self.integral = 0
  50.  
  51. def update(self, error, dt):
  52. derivative = (error - self.last_error) / dt
  53. self.integral += error * dt
  54. output = self.Kp * error + self.Ki * self.integral + self.Kd * derivative
  55. self.last_error = error
  56. return output
  57.  
  58. #Function definitions
  59.  
  60. #Motion capture angle output is in quaternions, translated to euler angles for ease of use
  61. #Ensure understanding of gimbal lock if you desire to change this conversion
  62. def euler_from_quaternion(x, y, z, w):
  63.  
  64. t0 = +2.0 * (w * x + y * z)
  65. t1 = +1.0 - 2.0 * (x * x + y * y)
  66. roll_x = math.atan2(t0, t1)
  67.  
  68. t2 = +2.0 * (w * y - z * x)
  69. t2 = +1.0 if t2 > +1.0 else t2
  70. t2 = -1.0 if t2 < -1.0 else t2
  71. pitch_y = math.asin(t2)
  72.  
  73. t3 = +2.0 * (w * z + x * y)
  74. t4 = +1.0 - 2.0 * (y * y + z * z)
  75. yaw_z = math.atan2(t3, t4)
  76.  
  77. return roll_x, pitch_y, yaw_z # in radians
  78.  
  79. #project a range of values onto another for ease of use in serial communication
  80. def mapValue(value, leftMin, leftMax, rightMin, rightMax):
  81. # Figure out how 'wide' each range is
  82. leftSpan = leftMax - leftMin
  83. rightSpan = rightMax - rightMin
  84.  
  85. # Convert the left range into a 0-1 range (float)
  86. valueScaled = float(value - leftMin) / float(leftSpan)
  87.  
  88. # Convert the 0-1 range into a value in the right range.
  89. return rightMin + (valueScaled * rightSpan)
  90.  
  91. #serial communication function
  92. def write_read(x):
  93. input = str(x)
  94. arduino.write(bytes(input, 'utf-8'))
  95. #time.sleep(0.005)
  96. data = arduino.readline()
  97. return data
  98.  
  99. #callback instantiation for publishers
  100.  
  101. def carCb (msg):
  102. global roll, pitch, yaw
  103. new_msg = TransformStamped()
  104.  
  105. orientation_q = msg.transform.rotation
  106. orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
  107. (roll, pitch, yaw) = euler_from_quaternion(orientation_list[0], orientation_list[1],orientation_list[2],orientation_list[3])
  108.  
  109. global xTransformCar
  110. xTransformCar = msg.transform.translation.x * 1000
  111. new_msg.transform.translation.x = xTransformCar
  112.  
  113. global yTransformCar
  114. yTransformCar = msg.transform.translation.y * -1000
  115. new_msg.transform.translation.y = yTransformCar
  116.  
  117. new_msg.transform.translation.z = msg.transform.translation.z * 1000
  118.  
  119. global angleRelativeDeg
  120.  
  121. roll = roll * radToDegMult
  122. pitch = pitch * radToDegMult
  123. yaw = yaw * radToDegMult
  124.  
  125. new_msg.transform.rotation.x = roll
  126. new_msg.transform.rotation.y = pitch
  127. new_msg.transform.rotation.z = yaw
  128. new_msg.transform.rotation.w = angleRelativeDeg
  129.  
  130.  
  131. carPub.publish(new_msg)
  132.  
  133. def ballCb (msg):
  134. new_msg = TransformStamped()
  135.  
  136. global xTransformBall
  137. xTransformBall = msg.transform.translation.x * 1000
  138. new_msg.transform.translation.x = xTransformBall
  139.  
  140. global yTransformBall
  141. yTransformBall = msg.transform.translation.y * -1000
  142. new_msg.transform.translation.y = yTransformBall
  143.  
  144. new_msg.transform.translation.z = msg.transform.translation.z * 1000
  145.  
  146. ballPub.publish(new_msg)
  147.  
  148.  
  149. #begin script
  150. rospy.init_node('continuous_change')
  151.  
  152. #instance of PID class
  153. pid = PID(Kp = 1.0, Ki = 0.05, Kd = 0.25)
  154.  
  155. #main loop
  156.  
  157. while not rospy.is_shutdown():
  158.  
  159. #time variable used to measure change in time between each loop instance for PID control
  160. startTime = time.time()
  161.  
  162. #collect and store data from ROS subscription into variables
  163. carSub = rospy.Subscriber ('/car1_vrpn/estimated_transform', TransformStamped, carCb)
  164. ballSub = rospy.Subscriber ('/ball_vrpn/estimated_transform', TransformStamped, ballCb)
  165.  
  166. xDelta = yTransformBall - yTransformCar
  167. yDelta = xTransformBall - xTransformCar
  168. distance = math.sqrt(pow(xDelta, 2) + pow(yDelta, 2))
  169.  
  170. #obtain and translate bearing angle from radians to degrees for ease of use
  171. angleRelativeRad = math.atan2(yDelta, xDelta)
  172.  
  173. angleRelativeDeg = angleRelativeRad * radToDegMult
  174.  
  175. #print statements for troubleshooting
  176. print("yaw: " + str(yaw))
  177. print("angle: " + str(angleRelativeDeg))
  178. print("distance: " + str(distance))
  179.  
  180. #obtain difference in current car angle to bearing angle
  181. yawPos = yaw >= 0
  182. relAnglePos = angleRelativeDeg >= 0
  183. angleErr = (angleRelativeDeg) - (yaw)
  184. overShoot = abs(angleErr) >180
  185. print("angle diff: " + str(angleErr))
  186.  
  187. #PID speed control
  188. dt = time.time() - startTime
  189. control_signal = pid.update(angleErr, dt)
  190. speed += control_signal * dt
  191.  
  192. #logic defining value mapping to ensure proper translation to serial as seen in previous tutorial
  193. #communicates speed value(s) or action value depending on if car angle matches bearing angle
  194. if(yaw > angleRelativeDeg + 1):
  195. print("Greater")
  196. if(not overShoot):
  197. speed = mapValue(speed, 0, 180, highBound, lowBound)/mapConst
  198. else:
  199. speed = -mapValue(speed, 180, 360, lowBound, highBound)/mapConst
  200.  
  201. value = write_read(int(speed))
  202. print(value)
  203.  
  204.  
  205. elif(yaw < angleRelativeDeg - 1):
  206. print("Lesser")
  207. if(not overShoot):
  208. speed = -mapValue(abs(speed), 0, 180, lowBound, highBound)/mapConst
  209. else:
  210. speed = mapValue(abs(speed), 180, 360, lowBound, highBound)/mapConst
  211.  
  212. value = write_read(int(speed))
  213. print(value)
  214.  
  215. elif(angleRelativeDeg -angleRangeConst < yaw < angleRelativeDeg + angleRangeConst):
  216. print("In Range")
  217. if(distance > 150):
  218. value = write_read(200)
  219. time.sleep(0.4)
  220. print(value)
  221. else:
  222. value = write_read(300)
  223. print(value)
  224. time.sleep(3)
  225.  
  226.  
  227. print("Speed PID: " + str(speed))
  228.  
  229. r = rospy.Rate(100)
  230. r.sleep()

Final Words

nxt_automation_alternative_practical_implementations.txt · Last modified: 2024/11/25 14:54 by hhameed