mobileBaseArduinoCode.ino 8.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405
  1. /*********************************************************************
  2. ROSArduinoBridge
  3. A set of simple serial commands to control a omniWheel drive
  4. robot and receive back sensor and odometry data. Default
  5. configuration assumes use of an Arduino Mega + four motor driver
  6. board. Edit the readEncoder() and setMotorSpeed() wrapper
  7. functions if using different motor controller or encoder method.
  8. *********************************************************************/
  9. #include <Thread.h>
  10. /* Serial port baud rate */
  11. #define BAUDRATE 57600
  12. /* Maximum PWM signal */
  13. #define MAX_PWM 255
  14. /* Include definition of serial commands */
  15. #include "commands.h"
  16. /* Sensor functions */
  17. #include "sensors.h"
  18. /* Motor driver function definitions */
  19. #include "motor_driver.h"
  20. /* Encoder driver function definitions */
  21. #include "encoder_driver.h"
  22. /* PID parameters and functions */
  23. #include "omniWheel_controller.h"
  24. #include "sound.h"
  25. #include "ledStrip_control.h"
  26. /* Run the PID loop at 30 times per second */
  27. #define PID_RATE 30 // Hz
  28. /* Convert the rate into an interval */
  29. const int PID_INTERVAL = 1000 / PID_RATE;
  30. static const int PowerContro_PIN = 52; //Mosfet Power controller sensor pin
  31. static const int alarm_powerControl_pin = 51; //alarm light powercontrol sensor pin
  32. /* Track the next time we make a PID calculation */
  33. unsigned long nextPID = PID_INTERVAL;
  34. /* Stop the robot if it hasn't received a movement command
  35. in this number of milliseconds */
  36. #define AUTO_STOP_INTERVAL 300
  37. long lastMotorCommand = AUTO_STOP_INTERVAL;
  38. /* Variable initialization */
  39. // A pair of varibles to help parse serial commands (thanks Fergs)
  40. int arg = 0;
  41. int index = 0;
  42. // Variable to hold an input character
  43. char chr;
  44. // Variable to hold the current single-character command
  45. char cmd;
  46. // Character arrays to hold the first,second,third arguments
  47. char argv1[48];
  48. char argv2[48];
  49. char argv3[48];
  50. // The arguments converted to integers
  51. long arg1 = 0;
  52. long arg2 = 0;
  53. long arg3 = 0;
  54. Thread myThread = Thread();
  55. /* Clear the current command parameters */
  56. void resetCommand()
  57. {
  58. cmd = '\0';
  59. memset(argv1, 0, sizeof(argv1));
  60. memset(argv2, 0, sizeof(argv2));
  61. memset(argv3, 0, sizeof(argv3));
  62. arg1 = 0;
  63. arg2 = 0;
  64. arg3 = 0;
  65. arg = 0;
  66. index = 0;
  67. }
  68. /* Run a command. Commands are defined in commands.h */
  69. int runCommand()
  70. {
  71. int i = 0;
  72. char *p = argv1; //p pointer for update pid parameter
  73. char *str;
  74. int pid_args[12];
  75. arg1 = atoi(argv1);
  76. arg2 = atoi(argv2);
  77. arg3 = atoi(argv3);
  78. switch (cmd)
  79. {
  80. case GET_BAUDRATE: //'b'
  81. Serial.println(BAUDRATE);
  82. break;
  83. case ANALOG_READ: //'a'
  84. Serial.println(analogRead(arg1));
  85. break;
  86. case DIGITAL_READ: //'d'
  87. Serial.println(digitalRead(arg1));
  88. break;
  89. case ANALOG_WRITE:
  90. analogWrite(arg1, arg2);
  91. Serial.println("OK");
  92. break;
  93. case DIGITAL_WRITE: //'w'
  94. if (arg2 == 0)
  95. {
  96. digitalWrite(arg1, LOW);
  97. }
  98. else if (arg2 == 1)
  99. {
  100. digitalWrite(arg1, HIGH);
  101. }
  102. Serial.println("OK");
  103. break;
  104. case PIN_MODE:
  105. if (arg2 == 0)
  106. {
  107. pinMode(arg1, INPUT);
  108. }
  109. else if (arg2 == 1)
  110. {
  111. pinMode(arg1, OUTPUT);
  112. }
  113. Serial.println("OK");
  114. break;
  115. case READ_ENCODERS: //'e'
  116. Serial.print(readEncoder(A_WHEEL));
  117. Serial.print(" ");
  118. Serial.print(readEncoder(B_WHEEL));
  119. Serial.print(" ");
  120. Serial.println(readEncoder(C_WHEEL));
  121. break;
  122. case RESET_ENCODERS: //'r'
  123. resetEncoders();
  124. resetPID();
  125. Serial.println("OK");
  126. break;
  127. case MOTOR_SPEEDS: //'m'
  128. lastMotorCommand = millis(); /* Reset the auto stop timer */
  129. if (arg1 == 0 && arg2 == 0 && arg3 == 0)
  130. {
  131. setMotorSpeeds(0, 0, 0);
  132. resetPID();
  133. moving = 0;
  134. }
  135. else
  136. {
  137. moving = 1;
  138. }
  139. AWheelPID.TargetTicksPerFrame = arg1;
  140. BWheelPID.TargetTicksPerFrame = arg2;
  141. CWheelPID.TargetTicksPerFrame = arg3;
  142. Serial.println("OK");
  143. break;
  144. case UPDATE_PID: //'u'
  145. while ((str = strtok_r(p, ":", &p)) != '\0')
  146. {
  147. pid_args[i] = atoi(str);
  148. i++;
  149. }
  150. AWheel_Kp = pid_args[0];
  151. AWheel_Kd = pid_args[1];
  152. AWheel_Ki = pid_args[2];
  153. AWheel_Ko = pid_args[3];
  154. BWheel_Kp = pid_args[4];
  155. BWheel_Kd = pid_args[5];
  156. BWheel_Ki = pid_args[6];
  157. BWheel_Ko = pid_args[7];
  158. CWheel_Kp = pid_args[8];
  159. CWheel_Kd = pid_args[9];
  160. CWheel_Ki = pid_args[10];
  161. CWheel_Ko = pid_args[11];
  162. Serial.println("OK");
  163. break;
  164. case SOUND_BEEP: //'f'
  165. if (arg1 == BASE_POWERON_BEEP)
  166. {
  167. basePowerOnBeep();
  168. }
  169. else if (arg1 == BASE_POWEROFF_BEEP)
  170. {
  171. basePowerOffBeep();
  172. }
  173. Serial.println("OK");
  174. break;
  175. case READ_PIDIN:
  176. Serial.print(readPidIn(A_WHEEL));
  177. Serial.print(" ");
  178. Serial.print(readPidIn(B_WHEEL));
  179. Serial.print(" ");
  180. Serial.println(readPidIn(C_WHEEL));
  181. break;
  182. case READ_PIDOUT:
  183. Serial.print(readPidOut(A_WHEEL));
  184. Serial.print(" ");
  185. Serial.print(readPidOut(B_WHEEL));
  186. Serial.print(" ");
  187. Serial.println(readPidOut(C_WHEEL));
  188. break;
  189. case LED_CONTROL: //'l'
  190. if (arg1 == STOPSTART_LIGHT)
  191. {
  192. myThread.enabled = false;
  193. }
  194. else if (arg1 == ENABLESTART_LIGHT)
  195. {
  196. myThread.enabled = true;
  197. }
  198. else if (arg1 == CLEAR_LIGHT)
  199. {
  200. clearLEDs();
  201. }
  202. else if (arg1 == RAINBOW_LIGHT)
  203. {
  204. startShow(RAINBOW_LIGHT);
  205. }
  206. else if (arg1 == WIPE_RED)
  207. {
  208. startShow(WIPE_RED);
  209. }
  210. else if (arg1 == WIPE_GREEN)
  211. {
  212. startShow(WIPE_GREEN);
  213. }
  214. else if (arg1 == WIPE_BLUE)
  215. {
  216. startShow(WIPE_BLUE);
  217. }
  218. else if (arg1 == CHASE_WHITE)
  219. {
  220. startShow(CHASE_WHITE);
  221. }
  222. else if (arg1 == CHASE_RED)
  223. {
  224. startShow(CHASE_RED);
  225. }
  226. else if (arg1 == CHASE_GREEN)
  227. {
  228. startShow(CHASE_GREEN);
  229. }
  230. else if (arg1 == CHASE_BLUE)
  231. {
  232. startShow(CHASE_BLUE);
  233. }
  234. Serial.println("OK");
  235. break;
  236. default:
  237. Serial.println("Invalid Command");
  238. break;
  239. }
  240. return 0;
  241. }
  242. void initSensorsPin()
  243. {
  244. pinMode(PowerContro_PIN, OUTPUT);
  245. digitalWrite(PowerContro_PIN, HIGH); //default enable Power controller
  246. pinMode(alarm_powerControl_pin, OUTPUT);
  247. digitalWrite(alarm_powerControl_pin, LOW); //default disable alarm light
  248. }
  249. // callback for myThread
  250. void lightCallback()
  251. {
  252. startShow(RAINBOW_LIGHT);
  253. }
  254. /* Setup function--runs once at startup. */
  255. void setup()
  256. {
  257. Serial.begin(BAUDRATE);
  258. initSensorsPin();
  259. initSoundPin();
  260. initCurrentSensor();
  261. initEncoders();
  262. initMotorController();
  263. initLedStrip();
  264. resetPID();
  265. myThread.onRun(lightCallback);
  266. myThread.setInterval(1500);
  267. }
  268. /* Enter the main loop. Read and parse input from the serial port
  269. and run any valid commands. Run a PID calculation at the target
  270. interval and check for auto-stop conditions.
  271. */
  272. void loop()
  273. {
  274. while (Serial.available() > 0)
  275. {
  276. chr = Serial.read(); //Read the next character
  277. if (chr == 13) //Terminate a command with a CR
  278. {
  279. if (arg == 1)
  280. {
  281. argv1[index] = '\0';
  282. }
  283. else if (arg == 2)
  284. {
  285. argv2[index] = '\0';
  286. }
  287. else if (arg == 3)
  288. {
  289. argv3[index] = '\0';
  290. }
  291. runCommand();
  292. resetCommand();
  293. }
  294. else if (chr == ' ') // Use spaces to delimit parts of the command
  295. {
  296. // Step through the arguments
  297. if (arg == 0)
  298. {
  299. arg = 1;
  300. }
  301. else if (arg == 1)
  302. {
  303. argv1[index] = '\0';
  304. arg = 2;
  305. index = 0;
  306. }
  307. else if (arg == 2)
  308. {
  309. argv2[index] = '\0';
  310. arg = 3;
  311. index = 0;
  312. }
  313. continue;
  314. }
  315. else // process single-letter
  316. {
  317. if (arg == 0)
  318. {
  319. cmd = chr; //The first arg is the single-letter command
  320. }
  321. else if (arg == 1)
  322. {
  323. // Subsequent arguments can be more than one character
  324. argv1[index] = chr;
  325. index++;
  326. }
  327. else if (arg == 2)
  328. {
  329. argv2[index] = chr;
  330. index++;
  331. }
  332. else if (arg == 3)
  333. {
  334. argv3[index] = chr;
  335. index++;
  336. }
  337. }
  338. }//end while()
  339. //run a PID calculation at the appropriate intervals
  340. if (millis() > nextPID)
  341. {
  342. updatePID();
  343. nextPID += PID_INTERVAL;
  344. }
  345. //Check to see if we have exceeded the auto-stop interval
  346. if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL)
  347. {
  348. setMotorSpeeds(0, 0, 0);
  349. resetPID();
  350. moving = 0;
  351. }
  352. if (myThread.shouldRun())
  353. myThread.run();
  354. }