The diagram below shows the subsystems and their major physical components. Connecting each physical component is an interface line that has to be physically connected and possibly addressed from a software perspective.

Chasis Sub-System:

After decades of thought about how to build a chassis, with many failed attempts using both wood and plexiglass, I have decided to purchase a chassis. There are two basic types; tracked and wheeled. There are many advantages with tracked vehicles however all Mars rovers are wheeled. All the Mars rovers utilize a design concept called rocker bogie suspension. There are no suitable off the shelf rocker bogie chassis available. There are however 4-wheel drive chassis. The selected chassis is the one that I selected back in 2005.

The number and size of components dictates the size of the rover central box and therefore the size of the rover. The rover of choice is the Nomad robot chassis available from servocity.com. The interior cavity or central box is 8” x 3.68” x 2.64” high. The overall size is 15.9” x 14” x 8” high. The chassis weighs 6.45 pounds and has a max speed of 5 MPH at 12 volts. The tires are 5.4” in diameter, perfect for uneven terrain. There are plenty of external mount points for sensors. The kit is made from components that remind me of the Erector Set of old.

1. Locomotion

Four motors are provided by the chassis kit. They are DC motors and they need motor controllers. The controllers of choice are Roboclaw motor controllers. Each board controls two motors. This requires two controller boards. These boards are very sophisticated.

The motors provided are 313 RPM heavy duty planetary gear motors that can propel the rover up to 5 MPH. They require a minimum of 6 volts with a maximum of 12 volts. The no load current is 0.52A and their stall current is 20A.

Given the stall amps, the proper size for the controller boards is the 2x15A boards which can handle a continuous draw of 15A and a surge of 30A. The size of these boards is 2.92” x 2.05” x 0.67” high. The Roboclaw setup software runs on Windows only. The manuals can be found at www.basicmicro.com.

The wires going to the motors need to be as short as possible. Given this and the fact that to turn the motors on one side need to run, the motor controllers should be mounted in the bottom cavities of the central box where the two side motor wires enter the interior cavity.

The Roboclaws can handle motors with encoders. With this added capability, the motors can measure distance traveled and control the speed of travel. This is a required capability. Two replacement motors were purchased to replace the rear motors. An encoder motor is paired with a non-encoded motor to control speed and distance traveled.

2. Roboclaw Interface

The Roboclaw has multiple interface types. The one that supports wheel encoding is Packet Serial Mode. This uses a serial port interface. The basic command consists of an address byte, a command byte, data bytes and a CRC16 byte. A micro-controller can address up to 8 Roboclaws.

The Roboclaws require a 5V and ground connection as well as a UART TX and RX interface. A basic example can be found at https://resources.basicmicro.com/standard-serial-bus-operation-with-arduino/ Examples from BasicMotion can be found at https://resources.basicmicro.com/category/arduino/.

The first step was to load the Motion Studio software onto a Windows laptop, connect a motor and 12v battery to the controller, then connect the controller to the PC with a USB cable. After launching the software and selecting the device, the firmware required updating. Once updated, they were both set to Packet Serial and one was set to address x128 which equates to address 0 or address 0x80 in Arduino speak and the other to address x129 or address 1 or address 0x81. The motors were connected and controlled from the software as a first test.

The main 12v battery and motor power wires connect to the screw connectors on one side of the controllers. The encoder wires and connections to the Arduino connect to the other side via the push pins. The simple motors only have +/- connections. The encoder motors have 6 wires. The red and black wires are the motor +/- wires. The other four connect to the pin side of the controller. The Yellow wire is Channel A, the brown wire is Channel B, the orange wire is sensor voltage + and the green wire is sensor voltage - wire.

3. Wheel Encoding

To facilitate position and speed motor control, wheel encoding is required. The Roboclaw controllers have encoding capabilities built in. However the motors require encoder hardware. There are alternate motors that include encoder hardware. These are found at Servo City, part #638328. Given the cost only the rear two motors will be swapped out.

There is a calibration procedure that must be run to calibrate each motor.

Power Sub-System:

The rover shall be autonomous in that it must be self-contained. The rover must be untethered, therefore it must have its own power supply. It is desirable to have the rover recharge itself such that it can run for months and simulate the capabilities of the Mars rovers.

1. Power Requirements

There are many varying power requirements in terms of voltage and amperage. The following table lists each device and its voltage and amperage requirement.

The motors require their own source and should be combined with the servos. These both have larger amperage requirements that spike during startup and stall conditions as motors typically do. Everything else is logic based and should run off a different battery. The total idle amperage for the logic circuits is ~1A with a surge amperage of 1.4A.

The power requirements that would be placed on 5v regulator would occur during Raspberry Pi startup. The total amperage would be approximately 1.2 amps. This is well within the 2 amp rating of the selected voltage regulator. Note that the PWM servo driver connects directly to the 6 volt battery pack and not through the regulator. The regulator is dedicated to electronic components that are more susceptible to power fluctuations.

The actual drive motors are connected directly to the 12v battery pack. Both power supplies are connected through the on/charge switch.

2. Batteries

Untethered operation is best accomplished with batteries. The batteries should be rechargeable. The batteries shall be sized such that the robot has plenty of run time yet does not have to spend a large amount of time recharging. The battery voltage must supply the power to both the motors and the CPUs.

The motors are isolated from the batteries by two Roboclaw motor controllers which have both power and logic battery needs. The motor voltage must be isolated from the CPU power to avoid power spikes created by the motors. The power battery needs a minimum of 6v and maximum of 34v. The current draw of each Roboclaw controller on the logic battery is 30mA for a total of 60mA.

The servos should also be run off a separate battery as they are motor based. They require a 5 to 6v source. The servos run off the logic battery directly. Only one servo will run at a time.

All the logic devices require a 5v power source. The voltage supply must be such that as the voltage drops, the converter can supply a constant 5 volts to the CPUs. Once the power supply falls to some point below 5 volts, the rover must find a way to recharge the batteries and prepare for an orderly shutdown. A 5v power regulator will be used. This will supply 5v even if the voltage drops below 5v. The voltage level of the battery must be measured on the battery side of the regulator.

The Arduino can be powered via the Vin pin and requires 9v - 12v. This means the two battery packs should be 12v. This is the same requirement as the wall wart adapter. For now the Arduino should be connected to the Power battery.

The Raspberry Pi can be powered via a GPIO pin, however unlike the Arduino the voltage must be exactly 5V. This requires a 5V voltage regulator. It is best to run the Raspberry Pi off its own battery to reduce voltage spikes. This battery can be 6V. Eventually it would be best to convert this battery to a 12V pack and run both the Raspberry Pi and Arduino off the same battery.

Given the various power requirements; 6V for the Raspberry Pi and 12V for the motors and the Arduino. This means two battery systems are required.

3. Roboclaw Requirements

For safety reasons, certain precautions are required for the power battery as the motors can act as generators and produce power that can be fed back into the system. A main power cut-off switch is required from the 12v battery and the Roboclaw controller. This should be a DPDT switch that also controls the logic power battery.

A pre-charge resister is required across the power side of the switch to reduce high in-rush current. This resistor needs to be a 1K resistor. A diode needs to be placed across the fuse to create a return path for the regenerative voltages. The logic battery does not need the resistor or diode, but it does require a switch and fuse.

The other side of the DPDT switch will put the rover in charge mode where an external charger can be attached to charging posts. The three positions of the switch are then charge/off/run.

4. Voltage Regulation

The selected step up/down voltage regulator from servocity.com can accept voltage inputs from 3V to 30V. It provides a fixed 5V output +/- 4%. There is protection against reverse voltage, over-current protection and over-temperature protection. The current draw should be less than 2 A. The Raspberry Pi Zero W uses 260mA at idle and 580 mA when stressed. There will be no USB items attached. This power is supplied using the 5V and GND pins of the GPIO (pins 2/4 and 6).

5. Recharging

The rover must be able to recharge itself. This can either be accomplished via solar cells or a recharging station. By using solar cells, the rover must be able to sense sunlight. By using a recharging station, the rover must be able to find its home base and plug into a power outlet. Recharging stations typically have a beacon that the rover can sense.

This rover design will utilize a solar cell recharging method. The solar cells capacity depends on the capacity of the batteries. The voltage supplied by the solar cells must be more than the voltage supplied by the batteries.

During initial assembly and check-out the capability exists to charge the rover from a wall wart charger. There is a switch on the side that toggles the rover between charge and run. If the switch is in the position towards the LED then it is in the run mode. To charge there are three screw posts on the other side of the on switch. The middle one is ground. The top one is used to charge the small battery pack and the lower one charges the larger battery pack.

6. Sensing Battery Voltage

Battery voltage of the power battery can be read from the Roboclaw controllers. Given that the logic feed is regulated, the voltage of the logic battery will be read via an A to D converter on the Arduino.

The Arduino can only measure from 0 to 5 volts. To measure the 6 volt battery voltage, two resistors are required to create a voltage divider. The voltage is measured against a reference voltage. This is measured at the Arduino 5v pin. The divider percentage is the voltage across both resistors divided by the voltage across the smaller resistor. There is a good tutorial at https://startingelectronics.org/articles/arduino/measuring-voltage-with-arduino/.

7. Solar Cells

The solar cells must be able to provide enough charge to charge the rechargeable batteries. The solar cells should be able to provide some amount of charge in an enclosed house, without direct sunlight. This is a good area where the robot can learn by exploring and remembering where the solar hot spots are and return to those spots when the power is low. This is a function of time. Direct sunlight appears throughout the house for brief periods throughout the day.

Note: The 6v battery may have to be swapped out with a 12v battery so both batteries are 12v to accommodate solar cell charging. That or two solar panels with different voltages are required.

Here is an article about solar charging.  https://blog.voltaicsystems.com/solar-charger-tutorial-part-3/

8. Alternative Power Supply

During the development phase of the project, battery power is not needed to power the rover. During this time, a 6 volt power converter can be used. Once a CPU is mounted in the rover, the battery should be utilized and the battery can be recharged with a wall wart. This simple circuit requires a diode for circuit protection and a switch to switch between external power and battery power. The input voltage of the alternate power supply should be 0.5 volts higher than the battery voltage due to the power drop across the diode.

Sensor Sub-System:

The rover shall be able to sense its surroundings. The surroundings include fixed physical objects and drop-offs. The surroundings also include the amount of available light to aid recharging, orientation and video feed to aid in navigation. BTW, to neatly organize wire bundles, wrap them in dental floss.

1. Sonar

The more complex object detection is detection from a distance. The detection need only occur in the forward direction. The distance to the detected object need not be measured for the specific required functionality of this rover.

There are cheap sonar sensors available. The measurement angle is 15 degrees. The range is 2 cm to 4 meters with an accuracy of 3mm. Given the angle of measurement, this sensor should be on a pan and tilt mast.

Upon a trigger signal, the sensor sends out eight pulses. The pulses travel at the speed of sound or 340 m/second which is also 0.034 cm/micro-second. The time it take a pulse to travel say 20 cm is 20 / 0.034 = 588 micro-seconds. This time would have to be divided by two since the echo travels out and back.

To start recording, the trigger pin must be low for at least 2 micro-seconds then raised high for at least 10 micro-seconds. The pulseIn() function is used on the echo pin to check for the pulse to go high then time how long it takes for it to go low.

Upon testing, it turns out that these sensors do not return stable results. For the main mast sensor, another technology is required.

2. Lidar

A better alternative, although more expensive solution, is Lidar. Lidar uses a laser or light pulse instead of sound. Garmin makes two Lidar units, the Lidar-Lite v3 and Lidar-Lite v3HP. The cost difference is minimal. The main difference is that the HP version uses less power and is therefore the option of choice. The cheaper one uses 105mA at idle and 130mA during acquisition. The HP version uses 65mA at idle and 85mA during acquisition.

The range of the v3HP is 131 feet max with a resolution of 1 cm. The accuracy is ~2.5 cm at less than 5m and ~10cm for greater than 5m. The spread of the beam is ~1/2 a degree. This makes the mapping function very accurate, more accurate than the sonar sensors.

The units communicate via I2C as well as PWM. The I2C address by default is 0x62. There is a 6-wire plug that contains 5v, ground, SDA, SCL, power enable and mode. The power enable and mode pins are used for PWM, which would not be used in this case. There should be a 1000uF electrolytic capacitor across the power and ground pins. The I2C supports 400kHz Fast Mode and operates internally at 3.3v, however it contains an internal level shifter and can run at 5v.

There is an Arduino library called LIDARLite that makes interfacing easy. A tutorial can be found at https://learn.sparkfun.com/tutorials/lidar-lite-v3-hookup-guide?_ga=2.191783016.374479072.1587138247-2089817138.1586905452.

The basic sensor’s dimensions are 0.8” x 1.9” x 1.6” long. The mounting holes are 1.08” x 1.15”.

3. Pan and Tilt

The pan and tilt mechanism consists of two micro-servos. These are connected to the Arduino using a PWM pin. Pan and tilt mechanisms are used for the camera. The distance detector uses only the pan servo. A total of 3 PWM pins are required for both mechanisms.

Due to the fact that each servo (4 so far) requires two digital pins (4 pins) and the limitations of the Arduino digital pins (14 total, 6 PWM pins), it has been decided to use a PWM driver board. This board uses I2C so there is no additional pin usage. The board is addressed by soldering up to 6 solder address bits. This board comes with a library for ease of coding. An example of how to use the board is found here: https://learn.adafruit.com/16-channel-pwm-servo-driver.

Given that the Lidar will create a narrow beam map of what is in front of the rover, a tilt servo is being dropped from the design. The Lidar will only pan right and left.

4. Drop-off Detection

To avoid falling down stairs, the rover shall be able to avoid drop-offs. The detection mechanism is dependent on the speed of the rover. After a certain speed, a touch sensor will not detect the precipice fast enough. In this case, a distance sensor must be employed.

A drop-off sensor is required on each end of the rover. Upon a drop-off detection, the rover shall immediately stop, cancel any subsequent commands in the command string and report back the situation. The remainder of the commands in the command sequence are discarded.

The drop-off detectors are run while the rover is moving, looking for a change if distance greater than about 5 cm.

5. Camera

The camera is the best human environmental awareness tool. The Raspberry Pi provides a dedicated camera interface as well as software to capture video and still images and send them to the web. The camera shall be mounted on a pan and tilt mast so the camera can survey the surroundings from a stationary position.

6. Light Detection

The rover shall be able to sense light. This allows certain behaviors such as light seeking or shadow seeking. Light seeking behavior allows the rover to effectively recharge the batteries. Light detection involves tracking the light to the strongest source. The stronger the sunlight found, the better the ability to charge the batteries. The light strength is measured via the solar panel voltage. The light strength is directly related to the solar panel output.

7. Time of Day

The rover shall be able to determine the time of day so it can create a solar map of when and were strong sunlight can be found. The date/time is maintained by the Raspberry Pi.

8. Distance Traveled

The rover shall be able to determine the distance it has traveled. This capability is obtained from the wheel encoding contained on the Roboclaw boards.

9. WiFi Signal Strength

WiFi signal strength is determined on the Raspberry Pi. This is required to override commands that may take the robot beyond control signal range. To get the WiFi signal strength use the command:

iwconfig wlan0 | grep -i signal

The output would be something like “Link Quality=41/70 Signal level=-69 dBm”

10. Orientation

The rover shall be able to determine its absolute orientation. This is an X-Y-Z orientation determined via an electronic compass. Orientation is useful for mapping the surrounding. A 9 degrees of freedom sensor can detect orientation and act as a compass. The sensor LSM9DS1 was considered, however the algorithms are mind numbingly difficult to get right. The more sensible solution is the more intelligent BNO055 device that produces absolute readings. This device interfaces using an I2C interface. Arduino libraries of code are available along with a tutorial at Adafruit https://learn.adafruit.com/adafruit-bno055-absolute-orientation-sensor/overview.

There are many items to be read from the sensor; absolute orientation(Euler vector), absolute orientation(Quaterion), angular velocity vector, acceleration vector, magnetic field strength vector, linear acceleration vector, gravity vector and temperature.
The device needs to be calibrated. There is a calibration section on the Adafruit website. All three sensors need to be calibrated; gyroscope, magnetometer and accelerometer. A very detailed magnetometer calibration can be found at https://thecavepearlproject.org/2015/05/22/calibrating-any-compass-or-accelerometer-for-arduino/.

CPU Sub-System:

Since 2005 there has been a boom in CPU development. The best general purpose small scale CPU by far is the Raspberry Pi. It solves many of the issues out of the box that had to be engineered by the older technology. The one thing it is not good at is handling hardware interrupts and real time control. For this the best solution is the Arduino.

The functions for the Raspberry Pi CPU include:

The functions for the Arduino CPU include:

1. Connections

The connections are limited on both the Raspberry Pi and Arduino. The Arduino Uno pinout with definitions can be found at https://www.circuito.io/blog/arduino-uno-pinout/. The following is a list of connected devices for each CPU and the method of connection.

Raspberry Pi:

DeviceConnectionPin Assignment
CameraDedicated PortDedicated Port
ArduinoSerialUSB
LCDI2C - addr 1Pin 27 - SDA0, Pin 28 - SCL0
PowerGPIO PinsPin 2 - 5V, Pin 6 - Ground

Arduino:

DeviceConnectionPin Assignment
Motor ControllersSerialPin PD11 - S1(TX), Pin PD10 - S2(RX)
Sonar Sensors (2)4 - data pinsPins PD4, PD5, PD6, PD7
Pan & Tilts (2)I2CPin A4 - SDA, Pin A5 - SCL
LidarI2CPin A4 - SDA, Pin A5 - SCL
Orientation SensorI2CPin A4 - SDA, Pin A5 - SCL
LCDI2CPin A4 - SDA, Pin A5 - SCL
Raspberry PiSerialUSB
PowerPinsVIN, GND

2. External Communications

The rover must be able to communicate with and be controlled by a human. The main interface will be via web pages. Physical human interaction is required to load programs, debug programs and start, stop and reset the CPUs.

2.1. Serial Port

Loading programs involves communicating between a desktop computer and the rover’s CPUs. This is typically a USB interface. For the Raspberry Pi this is achieved via SSH wirelessly. For initial setup, a keyboard/mouse/display was used. For the Arduino this is achieved via a USB connection. To avoid taking the rover apart every time a software update is required, USB extension cables are required. For the Raspberry Pi, a USB hub is used to connect the keyboard, mouse and USB thumb drive simultaneously.

2.2. Debugging

Initial debugging for the Arduino is performed using the serial USB connector and Arduino IDE freeware software. This type of debugging is useful in the early stages of development. This interface is also used to load a new program.

Once the rover is ready to start exploring on its own, a different type of debugging is required. This debugging is best accomplished via information written to an on-board LCD along with data written to the web pages.

2.3. LCD

The best LCD is a serial LCD. The interface to these LCDs is via data lines that accept commands and data. For both the Arduino and Raspberry Pi, there are HATs that are daughter boards that snap to the top of the CPU board. Since the boards are contained within the robot core, an extension cable is required to locate the two LCD screens outside the core.

An LCD board has too many data lines required to drive the display. As a result there is a way to use the I2C protocol to drive the display with a backpack board. This setup is described at https://learn.adafruit.com/i2c-spi-lcd-backpack/overview. This configuration can be used by both the Arduino and the Raspberry Pi. There are libraries that make this easy to code.

The Arduino will have multiple I2C devices and the LCD will have to be jumped to provide an address other than zero. The Raspberry Pi will use address zero. The address is changed by physically jumpering the board. To give the LCD an address of 1, solder the A0 jumper. The code then needs the following line of code: LiquidCrystal lcd(1);

3. Raspberry Pi

The Raspberry Pi can be thought of as the big brain. It solves the following problems out of the box: serial interface, bluetooth, USB interface, WiFi, disk space, timers, memory plus many more. It provides a very small footprint.

The initial testing was performed with an old Raspberry Pi 3. Due to pandemic limitations and a bit of common sense, the configuration has been modified to use a Raspberry Pi Zero. The Zero is less than half the size, but has the required interfaces; the camera I/F, the 40-pin GPIO I/F, a USB port and WIFI. The on-board RAM for a Raspberry Pi Zero W is 0.5 GB. The on-board disk space is dependent on the size of the Micro SD card installed.

3.1 Battery

The Raspberry Pi requires a 5V DC power supply, 3A via a USB port or the GPIO pins or via wall wart. The maximum power draw is 580 mA with a max of 1.2 A. For the rover, the battery pack should be attached to pins 2 (+5V) and 6 (GND). For the modern Pi you would need at least 6 AA batteries. The better solution is to get a lithium ion battery Pi HAT to power the Pi and another rechargeable battery for the rest of the robot. The Pi HAT power supply will act as an uninterruptible power supply to perform an orderly shutdown if the main battery fails. Possible battery solutions include: MakerFocus Battery pack and UPS, PiJuice HAT, Kuman Lithium Battery Pack, etal. Initially a backup battery for the Raspberry Pi will not be utilized.

3.2 Camera

The camera to use is the one that is compatible with the Raspberry Pi and plugs directly into its own port. There is a loadable software package that controls it, no software to write. It has been decided to use a camera with Infra-Red technology so pictures can be captured in the dark.

3.3 Web Communications

Web communications is accomplished via the WiFi interface and a web page. The details of this design is defined in the Software section.

4. Arduino

The Arduino can be thought of as the small brain providing lower level connections to the sensors without much thought or planning involved. The Arduino is an open source real time micro controller complete with A-to-D and D-to-A converters, built in RAM, serial port, external interrupts, PWM, plus timers. The Uno has 14 digital I/O pins, 6 analog inputs, one USB connection, and an ICSP header. Version 3 of the Uno has 2KB of SRAM and 1KB of EEPROM.

4.1 Battery

The Arduino is a low power CPU that is very flexible. The minimum requirements is 5V and a nominal current of 50mA. A full power draw depends on how many sensors are being powered.

4.2 Data Capture

It is best to have to Arduino drive the sensors and capture data because the Arduino has built in ADC capabilities. The captured data should then be transferred to the Raspberry Pi for consideration and transmission.

5. Sensor Communication

There are two built-in communications mechanisms to consider; SPI and I2C (Inter-Integrated Circuits). SPI is faster but limited to two connected slaves. I2C can have any number of slaves as long as they have a unique address. I2C also has a two wire hook-up versus the SPI which is very connection intensive. I2C is a short distance protocol which is the case for this project. I2C will be employed in the internals of the rover.

The two I2C wires require pull-up resistors. Use 2K resistors for the fast speed setting, about 400kbps and 10K resistors for the slow speed setting of 10kbps. The slower speed should be used as it is probably more reliable and not much data is being passed. All the devices must use the same voltage.

Each I2C slave requires a unique address. The following table lists the I2C devices connected to the Arduino and their assigned addresses.

DeviceAddressNotes
Lidar0x62Device will not respond to all call.
Servo Driver0x406 additional address pins if chaining these together.
Orientation Sensor0x28If ADR pin connected to 3v, address is 0x29.
LCD0x703 additional address pins if using multiple LCDs.

I2C is a synchronous protocol that has a clock signal line and a data line. One device is the master and one is a slave. There can be many slaves. In this case the Arduino should be the master because it communicates with all the sensors as well as the Raspberry Pi. The master generates the clock and initiates communications with the slaves. The protocol is a multi-master bus, however the Wire library does not support this. The protocol involves the sending of bytes. The first byte is the slave address followed by a data byte. Most of this is abstracted by the Wire library.

Wire.begin(address) initializes the Wire library. The master does not provide an address. Each transaction of data starts with Wire.beginTransmission(address) and ends with Wire.endTransmission(). Within this transaction you use Wire.write(data) Wire.read() and Wire.requestFrom(address, # of bytes). Wire.read() is used to read a byte of data. Wire.write() is used to write data. A slave writes data when the master performs a requestFrom() call. A master writes data to the slave between beginTransmission and endTransmission calls. Data can be written as a string, a number or a series of bytes. Wire.onRequest() is used by a slave to set up a function to be called when a master requests data via the Wire.requestFrom() call. The Wire.onReceive() is used by the master to set up a function to be called when the slave sends data.

If I2C is used as the protocol between the Raspberry Pi and the Arduino then the Pi can only be a master and this will not work. For this interface, a simple serial connection will be used.

6. Raspberry Pi to Arduino Communication

A simple serial communications mechanism is used to communicate between the two computers. One option is to connect the Arduino UART, the Tx and Rx pins 0 and 1 with the Raspberry Pi UART, pins 8 and 10. A level converter should be used for safety. This turned out to be unreliable. Instead a simple USB to USB connection is used.

A good tutorial is https://roboticsbackend.com/raspberry-pi-arduino-serial-communication/.

Software wise the Arduino is read to go. To configure the Raspberry Pi, first load the pyserial library using > pip install pyserial. The Pi needs to know what the device name is. It should be /dev/ttyACM0 set to a baud rate of 9600.
Arduino code is simple. Setup using the command Serial.begin(9600). Then send something using the command Serial.println(“Hello”).

Hardware:

The rover has a central box cavity to contain the sensitive equipment such as electronic boards. Everything that is not absolutely required to be outside will be located inside the central box.

1. Wiring

The wiring diagram is shown below. It is simple in that most sensors can use the I2C protocol. The Roboclaw controllers use a serial interface. The two CPUs connect via a USB wire. The camera has a dedicated port on the Raspberry Pi.

1. Inside

The central box measures 8” x 3.68” x 2.64” high. Underneath the central box is a main beam that the wheel bars are attached to. This is unusable space. On either side of the main beam are void spaces that are protected by plating. These spaces will hold the motor controllers. The wires from the motors to the motor controllers should be as short as possible. The two battery packs should be mounted as low as possible. They are too large to mount in the lower void spaces, therefore they should be mounted on the floor of the central box. The two remaining large components are the two CPU boards. They will be mounted on the ceiling of the central box. Other various boards such as the 9 degree of freedom compass/tilt board will mount within the central box.

The diagram below shows the approximate location of items. The metal parts are black. The components are blue.

2. Outside

The items that mount on the outside of the rover are the items that absolutely require outside mounting. These include drop-off detectors, sonar mast, camera mast, solar panels and LCD panels.

There are three u-shaped rails mounted to the top, front and back of the central box. These rails are 1.5” x 1.5” and run the width of the central box. The drop-off detectors will mount on the front and rear rails looking downward. The sonar and camera pan and tilt mechanisms will mount on the top rail, one on each side. The solar panel will mount on the back half of the top of the central box. The two LCD panels will mount on the front half of the top of the central box.

The diagram below shows the approximate location of items. The metal parts are black. The components are blue.

Software:

The rover shall be programmed with commands similar to the Mars rovers in that a sequence of commands are transmitted and the rover carries out the commands. The commands may include travel ten feet then stop. During a command such as this, the rover needs to perform life saving maneuvers such as obstacle avoidance.

1. Commands

Various commands are available at two different levels; the operator to the big brain (Raspberry Pi) and the big brain to the small brain (Arduino). The operator sends higher level functions to the big brain which then may require multiple lower level functions to be sent to the small brain.

1.1 Higher Level Commands

The higher level commands consist of actions to perform such as movement commands. These commands would mimic the interactions used with a Mars rover. Commands are stacked up and sent as a block. A typical command sequence might be to rotate right, move forward 3 feet and then perform a Lidar scan. The commands are simple two letter ASCII mnemonics followed by data. The list is comma separated. The following table lists the commands.

CommandMnemonicDataReturn Data
Move ForwardMFDistance “, speed >#/td###None
Move BackwardMBDistance ", speed >#/td###None
Rotate RightRRDegreesNone
Rotate LeftRLDegreesNone
Read Lidar MapLMNoneLidar Map
Center CameraCCNoneNone
Capture ImageCINoneNone (image in “static”)
Rotate Camera RightCRDegreesNone
Rotate Camera LeftCLDegreesNone
Tilt Camera UpCUDegreesNone
Tilt Camera DownCDDegreesNone
Situational AwarenessSANoneCompass, Tilt, Drop-off, Power, Temperature Data
Situational ImagingSINoneLidar Map, Camera Image
Read CompassODNoneDegrees (0-360)
Read Tilt DataTDNoneX/Y/Z data
Read Drop-off DataDDNoneFront/Rear Distance
Read Power DataPDNoneSolar/Power/Logic Voltages
Read TemperaturesTENoneOrient/Robo-A/Robo-B

1.2 Lower Level Commands

The lower level commands consist of actions to perform such as movement commands or data retrieval. These commands are generated by the Raspberry Pi and sent to the Arduino. The commands are in binary format to reduce the amount of data transferred. The following table lists the commands.

Each command is sent as a string with blank delimiters. An example is a Rotate Right 15 degrees command. The command would be “7 15”. The response would either be data-less or include the requested data. The data-less return may return error text. If the Read Lidar command is successful, the returned data would be a distance value. Error responses are strings such as “Invalid Data”, “No Data” or “Invalid Command”.

CommandCmd #DataReturn Data
Unused0
Unused1
Test2None“Test”
Read Status3NoneStatus field
Unused4
Move Forward5Distance in inches, speed in % of maxNone
Move Backward6Distance in inches, speed in % of maxNone
Rotate Right7In DegreesNone
Rotate Left8In DegreesNone
Read Compass9NoneDegrees (0-360)
Pan Camera10DegreesNone
Tilt Camera11DegreesNone
Center Camera12NoneNone
Pan Lidar13DegreesNone
Center Lidar14NoneNone
Read Lidar15NoneDistance in centimeters
Read Power Voltage16NoneVoltage
Read Logic Voltage17NoneVoltage
Read Solar Voltage18NoneVoltage
Read Front Drop-off19NoneDistance in centimeters
Read Rear Drop-off20NoneDistance in centimeters
Read Tilt X21NoneTilt in degrees
Read Tilt Y22NoneTilt in degrees
Read Tilt Z23NoneTilt in degrees
Read Temp. 9 DOF24NoneTemperature in degrees F
Read Temp. Robo-A25NoneTemperature in degrees F
Read Temp. Robo-B26NoneTemperature in degrees F

The status field is a bitmap with each bit representing a good/bad status. The bit positions are:

BitStatus
0LCD Status
1Roboclaw A Status
2Roboclaw B Status
3Orientation Status
4Servo Driver Status
5Lidar Status
6Front Sonar Status
7Rear Sonar Status

2. Map

The map shows in two dimensions where the rover has been. This is based on the direction and distance information from the orientation sensor and the rear motor data. The map should scale based on where the rover has been. The starting position is always (0, 0). Each point should display (x, y) location from the starting point. North is always up.

3. Sunlight Map

The sunlight map is a dynamic map of the surroundings that gives the rover the best possible recharge possibilities based on the time of day. The rover should start mapping from the starting position. This allows both maps to be overlaid. The map should contain time based locations of sunlight that is beyond the charging voltage threshold.

The length of day changes with the seasons. The angle of sunlight changes with the time of day. The rover does not care what the exact time is so much as the relative times and sunlight intensity. Once an intense hot spot is detected, the rover knows that same spot will be illuminated exactly 24 hours later.

This function depends on the light sensor, the compass and the distance traveled. This is the most complex and highest level behavior. This is also the most important to the survival of the rover.

4. Arduino Software

Arduino software is unique in that it has its own IDE and is all open source. The code is written in C++. The Arduino has no operating system and can only load and run a single program at a given time. The main code structure consists of a startup method followed by a main loop that runs continuously.

4.1 Startup

The startup sequence should proceed from the inside out. The Arduino, being the I2C master, is critical in the start up sequence. The sensors should be initialized and tested first followed by the interface to the Raspberry Pi to start receiving commands. The following is a list of the start up sequence. Each sensor should be initialized, configured and tested. Once successful, the status of each sensor is displayed on the LCD.

  1. LCD
  2. Lidar Pan
  3. Camera Pan and Tilt
  4. Lidar sensor
  5. Front Drop-off sensor
  6. Rear Drop-off sensor
  7. Orientation sensor
  8. Roboclaw A
  9. Roboclaw B
  10. Raspberry Pi

4.2 Main Loop

DO NOT USE THE delay() STATEMENT!!! This is a busy wait. The command is ubiquitous in on-line examples.

The main loop only needs to check the UART interface for the next command. When the rover is moving there are various tasks the Arduino needs to perform simultaneously. These are to check each drop-off sensor and check for too much tilt. The drop-off and tilt sensor checks are only run when the rover is moving. This involves a sub-loop while the movement command is running.

The UART interface is checked periodically for a command to execute. Only one command is received at a time. The higher level does not send the next command until a reply is sent from the Arduino. The replies are either an ACK or NAK and reason for failure.

5. Raspberry Pi Software

Raspberry Pi code is written in Python script using Flask on the uWSGI web server. This is a very light weight web site solution.

5.1 Web Interface

The web interface will serve out camera images, pages of data giving situational awareness to the operator, a command interface that generates a command string to send to the rover, a test page that sends individual commands to the Arduino, a position/sunlight map and a Lidar chart.

The web interface definition along with the Raspberry Pi setup and configuration is defined in a separate document named Pi Setup.odt.

The /index or home page displays subsystem status so you know the functional status of the rover.

The /status or situational awareness page displays various data values such as direction, tilt, forward distance scan, power values, drop-off distances, camera orientation and sunlight strength.

The /command page consists of the list of possible commands and as each command is selected, the optional data is input, then the command is added to the command string.

The /test page allows for individual low level Arduino commands to be sent directly to the Arduino. This is for testing purposes.

The /images page allows management of images and sets an image to display. This is a checkbox list of all images.

The /view page displays still images.

The /lidar page displays a graphical representation of the Lidar results in a 180 degree sweep.

The /sunlight page displays a graphical representation of the sunlight strength for a given hour of the day on a two dimensional map of the travel path.

The /restart page restarts the Arduino from the main menu. Note that there is no sub-menu, it simply restarts.

The /shutdown page shuts down the Raspberry Pi from the main menu.

The /help page provides help for commands and other explanations of capabilities.