In the first part of this lab you’ll assemble the mobility subsystems on your robot: the front drive wheels, the rear omni wheel, the lower and upper plates, the battery, and the org. For now, the robot will receive remote commands by a USB tether to a PC.
In the second part of the lab you’ll write code for the org to implement forward and inverse velocity and position kinematic control. This will be based on a library of supporting code we have prepared for the org called the OHMM Monitor.
We have prepared an archive file of sourcecode that you’ll use in this lab. Follow similar instructions as for lab 0 to download and unpack it.
We ask you not to modify the files you unpack from the lab tarball. You will write code that refers to these files and that links to their generated binary libraries. Please do not work directly in the provided files, in part because we will likely be posting updates to the lab tarball.
lab1/src/libpololu-avr
run make
to build the Pololu AVR library.lab1/src/mottest
run make
to build the motor test program.In lab1/src/org/monitor
run
> make
> make program
to build the OHMM Monitor library and executable and to upload the executable to the org. (In the event that we distribute an updated lab tarball, you will need to re-make
in both libpololu-avr
and in monitor
, and also re-program
in monitor
.)/dev/ttyACM1
. See the comments in lab1/src/org/monitor/minicom.acm1
and lab1/src/org/monitor/kermit.scr
for details. Once your terminal program is running, reset the org and you should see a banner and prompt. Follow the instructions to get a command list. Explore the commands. Make sure your robot is up on a jackstand if you try any of the motor commands.lab1/src/org/monitor/ohmm/*.h
. There is both general documentation at the top of the file and documentation for each public macro and function further down.Make a checkout of your group svn repository on your ohmmkey as a sibling directory to the lab1
directory you unpacked from the lab tarball:
> svn co https://trac.ccs.neu.edu/svn/robotics-class/g?
where ? is your group number. If prompted, supply your CCIS username and password. Your group members have read/write access to this repository, and the course staff has read access.Change directory on your ohmmkey so that you are in the base directory of your svn repository checkout (i.e. you are in the g?
directory that was created when you ran the command above), then run the commands
> mkdir lab1
> d=../lab1/src/org/monitor
> cp $d/makefile_AVR.inc $d/main.c ./lab1/
> cp $d/makefile-lab ./lab1/makefile
> svn add lab1
> svn commit -m "added lab1 skeleton"
> cd lab1
> make
> make program
This sets up the directory g?/lab1
in the SVN repository in which you will write all code for this lab. The makefile should not need to be modified: it is pre-configured to find the Pololu AVR Library and the OHMM Monitor library in ../../lab1/src/org/monitor
. It also will automatically compile and link all .c
files you create in the same directory (and .h
files in the same directory will be found as long as you use the syntax #include "foo.h"
, i.e. use double quotes, not angle brackets).
Study carefully the cmd
module in the monitor, and how monitor shell commands are registered and implemented in the other modules. Implement a new monitor command dgvw
(drive get ) which takes no arguments and which returns two floating point numbers. The first return is the current robot forward velocity
in mm/sec and the second is the current CCW angular velocity
in rad/sec. These should be calculated from the results of
motGetVel()
using the velocity FK transformation. You will also need to supply the wheel radius and baseline
(distance between the wheel contact points on the ground). You can either add monitor commands to set/get these interactively (start them out with reasonable hardcoded defaults), or just use
#define
constants.
If you study the code carefully, you may notice that we use fixed point math internally in the mot
module; you should not need to do this. Just use float
math as you usually would. It will work but you should realize that all floating point operations are implemented by avr-gcc
as software subroutines, and as such will be much slower than integer operations. There should be plenty of cycles in this context.
You may find the HOST_DBG()
macro in the host
module and the script find-in-src.sh helpful.
Implement a new monitor command dsvw
(drive set ) which takes two floating point arguments,
and
in the same units as above, and which makes a corresponding call to
motSetVel()
after applying the velocity IK transformation.
Implement a new monitor command dsvl
(drive set ) which takes two floating point arguments
and
.
is the forward speed command in mm/s as above.
is the desired turning radius in mm. Make the two arguments have the same semantics as the two arguments to the iRobot Create
drive
command, which is documented on page 9 of the Create Open Interface v2. Figure out the transformation from to
and then continue as above.
Implement a new monitor foreground task that implements incremental odometry as developed in Lecture 3. Register the task to run at 20Hz. Assume the robot pose starts at , i.e. aligned to world frame. Use units of mm for
and radians for
. Each time the task runs, use
motGetPos()
to get the new wheel rotation amounts, subtract their values from the last update, then update accordingly.
Implement a new monitor command dgp
(drive get pose) that returns the most recently calculated as three floating point numbers. Note that you will not need to worry about the handler for this command running concurrently with the periodic odometry update task — they are both run in the foreground, and foreground tasks never interrupt each other.
Implement a new monitor command drp
(drive reset pose) that resets .
Implement a new monitor command df
(drive forward) that takes one floating point argument: the number of millimeters to drive forward (or backward, if negative). Upon receipt of the first df
command, the robot should start moving in the indicated direction. For now, hardcode a reasonable travel speed, say 100mm/s. The command handler must not block while the motion completes, but instead should register a periodic task to check for completion, and then return quickly so that other foreground tasks can run. You can also modify your odometry task so that it additionally checks for completion of the current drive command. Of course, the desired position will not exactly be reached; you will need to define a reasonable tolerance interval within which the drive is considered complete.
If another df
command is received while one is ongoing, the new command should be queued. Implement a queue that can store up to at least 32 drive commands. (You may wish to study the code in the task
and cmd
modules which uses arrays of structs to store other kinds of data.) When a drive command completes, the next one, if any, should be popped off the queue and begin execution.
Implement a new monitor command dgs
(drive get status) that returns one int, which the number of commands currently waiting in the drive command queue, if any, plus one if a command is currently executing. Thus, dgs
should return zero iff (if and only if) no command is executing and none are queued.
Implement a new monitor command dst
(drive stop) that pauses the current drive command, if any. Also implement a companion command drs
(drive resume) that resumes driving if paused.
Implement a new monitor command dri
(drive reinit) that stops any ongoing drive command, if any, and then drops it and any other queued drive commands.
Implement a new monitor command dt
(drive turn) that takes one floating point argument: a turn-in-place angle in CCW radians. The execution semantics of dt
should parallel those of df
.
Devise two experiments: one to help you calibrate your estimated value for the wheel radius , and another to help you calibrate the estimated value for the baseline
. Use these to try to optimize the accuracy of drive sequences. For example, try driving in a square or triangle pattern where the robot should ideally return to its original pose. (The calibration experiments should actually be simpler, e.g. just one
df
for the calibration and one
dt
for the calibration.)
You will be asked to demonstrate your code for the course staff in lab on the due date for this assignment; 30% of your grade for the lab will be based on the observed behavior. Mainly want to see that your code works and is as bug-free as possible. To a much lesser extent, we will also consider the accuracy of your odometry and drive sequences. We will not consider the robot speed as long as it is not absurdly slow (e.g. it should be able to drive a 1m square pattern in no more than ~2 minutes).
The remaining 70% of your grade will be based on your code, which you will hand in following the instructions on the assignments page by 11:59pm on the due date for this assignment. We will consider the code completeness, lack of bugs, architecture and organization, documentation, syntactic style, and efficiency, in that order of priority. You must also clearly document, both in your README and in code comments, the contributions of each group member. We want to see roughly equal contributions from each member. If so, the same grade will be assigned to all group members. If not, we will adjust the grades accordingly.