Difference between revisions of "Training Projects"
(→Part I: Blink light as commanded by ROS topic) |
(→ROS Arduino Project) |
||
Line 48: | Line 48: | ||
Try compiling and uploading to the Due. It shouldn't do anything. Remember to shut off the wheels while uploading, otherwise they may spin. Now we need to write the code on the Pi that will send instructions via the <code>/led</code> topic. | Try compiling and uploading to the Due. It shouldn't do anything. Remember to shut off the wheels while uploading, otherwise they may spin. Now we need to write the code on the Pi that will send instructions via the <code>/led</code> topic. | ||
+ | |||
+ | Now, on the Raspberry PI, to start ROS and connect to the Due, write: | ||
+ | <code>$ . start.sh serial_only &</code> | ||
+ | |||
+ | To turn the LED on, you can send this command (replace true with false to turn it off): | ||
+ | <code>$ rostopic pub /led std_msgs/Bool "data: true"</code> | ||
+ | |||
+ | Now, let's write a ROS node. It will be written in Python. You can put this anywhere, but by convention it'll go in ~/ros_ws/src/bike/scripts (note: check this path, might not be correct). Save it as led_node.py: | ||
+ | |||
+ | <pre>import rospy | ||
+ | from std_msgs.msg import Bool | ||
+ | import time | ||
+ | rospy.init_node("led") | ||
+ | pub = rospy.Publisher("/led", Bool, queue_size=10) | ||
+ | state = True | ||
+ | while True: pub.publish(state); state = not state; time.sleep(1)</pre> | ||
+ | |||
+ | And then you can run it with python led_node.py. The LED should blink on and off every second. | ||
==== Part II: Rotate wheel as commanded by ROS topic ==== | ==== Part II: Rotate wheel as commanded by ROS topic ==== | ||
=== GPS Project === | === GPS Project === |
Revision as of 19:57, 16 April 2019
These training projects are meant to familiarize new members with the theory behind the bike and the bike itself.
Contents
DC Motor Control Project
- 1: Test DC Motor using Arduino
Reference Circuit: https://learn.adafruit.com/adafruit-arduino-lesson-13-dc-motors/overview
- 2: One DOF Helicopter: Build a chopstick-fan that stays horizontal when disturbed
Reference: ECE 4760 Lab http://people.ece.cornell.edu/land/courses/ece4760/labs/f2018/lab4_helicopter.html
ROS Arduino Project
ROS stands for the Robotic Operating System, and despite the name is not an operating system. It provides a framework for programs in different languages running on different platforms to communicate. A running program is called a ROS node. Nodes can be started and stopped independently, and there must be a ROS core running (a special kind of node) for communication to occur.
One way nodes can communicate is via a ROS topic. A node will use a topic to publish messages, and other nodes may subscribe to the topic. A given topic's messages always have the same message type (i.e. data type). There are many possible data types; many will be familiar to you from previous programming languages.
For these programs, you will need the Arduino IDE. This open-source software allows you to write code and upload it to the board. Click here to download it.
Part I: Blink light as commanded by ROS topic
This program will allow an LED on the bike to be controlled by a ROS topic. It will subscribe to a topic called /led
, and whenever a boolean value appears the program will set the state of the LED to that value.
You may need a new library to compile ROS code. If #include <ros.h>
compiles without an error, then you can skip this step. Otherwise, download the file "ros_lib.zip" in the bike drive folder. In the Arduino IDE, go to the menu item "Sketch > Include Library > Add .ZIP Library..." and navigate to where you downloaded "ros_lib.zip", and select it.
You may also need the library for the Due. Go to the "Tools > Board" submenu. If an entry called "Arduino Due (Programming Port)" appears all the way at the bottom, then you can skip this step. Otherwise, in the same submenu ("Tools > Board"), click on "Boards Manager..." at the top. Type "Due" into the search bar, and install the package that comes up. Now, from the "Tools > Board" menu, select "Arduino Due (Programming Port)", and plug the wire from the programming port on the Due into a USB port on your computer. You should now be able to upload code to the Due.
Let's write some code. Start a new program in the Arduino IDE ("File > New"), and add the following lines to it, at the very top of the file, outside of the functions that are already there:
#include <ros.h> #include <std_msgs/Bool.h> #define RED_LED 22 ros::NodeHandle_<ArduinoHardware, 1, 3, 500, 500> nh; bool led_state = false; // Variable for whether the LED is on void updateInstruction(const std_msgs::Bool&data) { led_state = data.data; } ros::Subscriber<std_msgs::Bool> led_sub("/led", &updateInstruction);
Let's go over this code. The #include
line includes other source files into the current source file. For header files and standard files, use #include <file_name>
and for user defined files, use #include "file_name"
. Including ros.h
includes all the headers necessary to use the most common public pieces of the ROS system and including std_msgs/Bool.h
includes the std_msgs/Bool message. Next, the #define
directive creates a macro, which is the association of an identifier or parameterized identifier with a token string. The compiler will then substitute the token string for each occurrence of the identifier in the source file. In this code, we are substituting every instance of RED_LED
with 22. The line ros::NodeHandle_<ArduinoHardware, 1, 3, 500, 500> nh
creates a NodeHandle, which handles all node initialization and communication. The arguments set the NodeHandle to have 1 publisher, 3 subscribers, 500 bytes for input buffer, and 500 bytes for output buffer. We then write a function updateInstruction()
that will store the data in the message in the variable led_state
. Finally, using the line ros::Subscriber<std_msgs::Bool> led_sub("/led", &updateInstruction)
, we create a subscriber to the \led
topic that calls the updateInstruction()
function whenever a new message arrives.
In the setup() function, paste this code:
nh.initNode(); nh.subscribe(led_sub); Serial.begin(115200); pinMode(RED_LED, OUTPUT);
Let's go over this section of code. nh.initNode()
initializes the ROS node. You can only have one node in a rosserial device so you can only call initNode()
once. In the next line, we subscribe to the led_sub
subscriber created earlier. Serial.begin(115200)
sets the data rate in bits per second for serial data transmission. For more information about begin()
see here. Then we set the pin RED_LED
to behave as an output.
Finally, in the loop() function, paste this code:
digitalWrite(RED_LED, led_state); nh.spinOnce();
Since the RED_LED
pin has been configured as an OUTPUT
, digitalWrite(RED_LED, led_state)
will set the voltage of the pin to the corresponding value: 5V for true
and 0V for false
. Because ROS pushes the subscriber callbacks onto a queue without calling them immediately, writing nh.spinOnce()
will tell ROS to process all the callbacks. Here is more information about callbacks and spinning.
Try compiling and uploading to the Due. It shouldn't do anything. Remember to shut off the wheels while uploading, otherwise they may spin. Now we need to write the code on the Pi that will send instructions via the /led
topic.
Now, on the Raspberry PI, to start ROS and connect to the Due, write:
$ . start.sh serial_only &
To turn the LED on, you can send this command (replace true with false to turn it off):
$ rostopic pub /led std_msgs/Bool "data: true"
Now, let's write a ROS node. It will be written in Python. You can put this anywhere, but by convention it'll go in ~/ros_ws/src/bike/scripts (note: check this path, might not be correct). Save it as led_node.py:
import rospy from std_msgs.msg import Bool import time rospy.init_node("led") pub = rospy.Publisher("/led", Bool, queue_size=10) state = True while True: pub.publish(state); state = not state; time.sleep(1)
And then you can run it with python led_node.py. The LED should blink on and off every second.