AION ROBOTICS Documentation

_images/dirt-m.gif

General product documentation for all products available from AION ROBOTICS

AION ROBOTICS GitHub

Contents:

AIONio

Getting Started

AIONio is a complete system image that enables seamless advanced control of AION ROBOTICS companion computer equipped vehicles.

Companion Computer: Recommended Use:
Jetson TX2 High performance edge computing
Jetson Xavier Ultimate performance edge computing

Jetson Hardware Info

Running the latest release of JetPack, you’ll have access to a full Ubuntu desktop and all the great features of linux. Whether developing Simultaneous Localization and Mapping applications, Deep Neural Networks, Object Detection and Tracking, AIONio provides an excellent foundation to get you going quickly.

Included:

  • Full Ubuntu Operating System
  • ROS installation
  • AIONio ROS control package
  • MavROS - MAVlink communication node
  • Telemetry and Message routing between Autopilot, Companion and remote Computers. (Serial/UDP/TCP)
  • Networking support for:
    • WLAN - WiFi
    • LAN - Ethernet, p2p, LTE
    • Serial
  • H264 video streaming
  • NVIDIA Jetpack
    • TensorRT
    • cuDNN
    • VisionWorks/OpenCV
    • CUDA
    • Multimedia API
    • L4T
    • Computer Vision

ROS Packages

Repo Package Function Status
aion_io aion_control
  • Control vehicle using cmd_vel messages
  • Publish Autopilot sensors as ROS topics
Complete
aion_io aion_descriptions
  • Vehicle URDFs and Mesh Files
Complete
aion_io aion_simulator
  • Gazebo Config and launch files
  • Simple Teleop node for using a playstation Controller
Complete

AION ROBOTICS GitHub

Add on packages are available for purchase from AION ROBOTICS

Calibrate Autopilot

UGV Instructions [HERE]

The calibration example is provided using Mission Planner Ground Control Station [HERE]

Vehicle Bringup

  1. Power on the vehicle
  2. Connect to the WiFi network with a host computer.

Tip

The name of the network is AIONio- plus the last four hexadecimal digits of the vehicles unique mac address. For example: AIONio-c71a

  1. The default passphrase to connect to the network is aionrobotics

4. Open a terminal and ssh to the UGV over wireless network:

ssh -X aion@10.0.1.128

Username aion

Password aion

5. launch AIONio:

cd ~/AIONio_ws
roslaunch aion_control aion_io.launch
  1. Verify Autopilot sensors are streaming to ROS:
  • To view GPS location:
rostopic echo /mavros/global_position/global
  • To view a list of all ROS topics:
rostopic list
  • To view the output of any topic:
rostopic echo <topic_name>
  1. Follow the appropriate vehicle control guide below.

UGV Control

1. Arm the vehicle:

rosrun mavros mavsafety arm

Note

Vehicle must have a GPS lock to arm in autonomous modes. Documentation for GPS denied/indoor navigation coming soon.

Tip

You can also Arm using an RC transmitter or GCS such as AION ROBOTICS C3, Mission Planner etc. For instructions see vehicle specific documentation.

2. Change vehicle mode:

rosrun mavros mavsys mode -c GUIDED
Control Mode Function
MANUAL
  • Manual control of the vehicle
AUTO
  • Begin ArduPilot Point-N-Click waypoint mission
GUIDED
  • ROS control of Autopilot

For full MavROS documentation see [HERE]

3. To move the vehicle, we must publish cmd_vel messages. Open another terminal, connect to the vehicle and launch rqt:

rqt
  1. Add topic to publisher:

/mavros/setpoint_velocity/cmd_vel

geometry_msgs/Twist

cmd_vel

  1. Under the rqt “Plugins” tab, select “Publishers>Robot Steering”

Warning

UGV will move when you output cmd_vel! Be ready to hit stop!

Note

This example control tool works by publishing cmd_vel messages which MavROS is subscribed to. cmd_vel messages are used to physically control the UGV in the real world and serve as the base for you to build advanced integrations from.

Copter Control

Warning

ROS control of UAS is for advanced users only. Serious risk of injury or property damage! Read these instructions in full several times before attempting to execute in real life. Safe operation is the responsibility of the user.

1. Change aircraft mode:

rosrun mavros mavsys mode -c GUIDED
Control Mode Function
LOITER
  • GPS/Alt stabilized manual flight
RTL
  • Return to location when first Armed
GUIDED
  • ROS control of Autopilot
LAND
  • Lands the aircraft

2. To control the vehicle while in flight, we must publish cmd_vel messages. Open another terminal, connect to the vehicle and launch rqt

rqt
  1. Add topic to publisher:

/mavros/setpoint_velocity/cmd_vel

geometry_msgs/Twist

cmd_vel

  1. Under the rqt “Plugins” tab, select “Publishers>Robot Steering”.

Note

This example control tool works by publishing cmd_vel messages which MavROS is subscribed to. cmd_vel messages are used to physically control the UGV in the real world and serve as the base for you to build advanced integrations from. You will use this tool to move the aircraft in flight.

Warning

PROPS WILL BEGIN SPINNING WHEN ARMED!

5. Return to the first terminal to Arm the vehicle:

rosrun mavros mavsafety arm

Warning

PROPS WILL BEGIN SPINNING WHEN ARMED!

Note

Vehicle must have a GPS lock to arm. Documentation for GPS denied/indoor navigation coming soon.

Tip

You can also Arm using an RC transmitter or GCS such as AION ROBOTICS C3, Mission Planner etc. For instructions see vehicle specific documentation.

6. To take off:

rosrun mavros mavcmd takeoff

You will use the “Robot Steering” sliders to move vehicle during flight.

Warning

Vehicle will move when you output cmd_vel! Be ready to return slider to zero position to stop! This is a primitive control example only and should NOT be used for normal operation.

7. To land:

rosrun mavros mavcmd land

Useful Tools

  • To visualize all active nodes/topics:
rqt_graph

Tip

To use rqt_graph remotely without setting up ROS networking, you may want to export the TX2 display to your remote machine.

To do so:

export DISPLAY=:10

Complete list of ROS tools [HERE]

Running ROS remotely

AION ROBOTICS vehicles ship with ROS networking configured as Master. You can run ROS nodes and programs such as rviz on a remote computer by installing ROS and configuring it to use the vehicle as Master.

To point the remote computer to the vehicle (ROS Master) add the following lines to its .bashrc file:

export ROS_MASTER_URI=http://IP_OF_VEHICLE:11311
export ROS_HOSTNAME=IP_OF_THIS_COMPUTER

If you are using Ubuntu, you can substitute IP_OF_VEHICLE with the hostname of your vehicle. The hostname is the same as the WiFi network name followed by .local.

Following our previous example above, the hostname would be AIONio-c71a.local. Otherwise, you will substitute this with the actual IP address of the vehicle.

Likewise if using Ubuntu, you may substitute IP_OF_THIS_COMPUTER with your computers hostname followed by .local or again, with the computers IP address.

For more detailed information or troubleshooting tips on configuring ROS networking look at the ROS Documentation

Video Streaming

Video streaming is enabled by default.

  • To use this feature, simply plug in a USB Camera and it will automatically start an H264 UDP stream to port 5600

Tip

To access the control panel, type 10.0.1.128:8000 into a connected devices web browser.

Factory Reset

To factory reset a TX2 equipped vehicle see [HERE]

Vehicles

Mechanical user guides for AION ROBOTICS vehicles:

R Series Documentation

The R series represents AION ROBOTICS smallest weight class UGVs.

  • The R1 is a 4x4 skid-steer UGV designed for educational or professional research & development applications.
  • The R6 is a 6x6 light commercial, weatherproof UGV configurable to customer specifications.

R1 UGV

Model Specifications
_images/Aion-Robotics-R1-Gravel-Anamorphic-Flare-Front-25.jpg _images/R1Features.jpg _images/r1-specs-inch.PNG _images/r1-specs-cm.PNG
Package Options

The R1 UGV is a powerful turn-key 4x4 skid-steer rover designed from the ground up to meet the needs of students, enthusiasts and professional research & development teams alike.

A true indoor/outdoor capable robotics platform, its powder coated chassis is made from heavy gauge Aluminum and it rolls on 6” shock absorbing, foam filled tires.

This rover is so powerful its capable of a vertical wall climb given up to 7ft-lbs (9.5Nm) of torque thanks to four direct drive DC gear motors w/ encoders.

It weighs roughly 11lbs (5Kg) ready-to-run and comes with a front facing window to protect video gear as well as plenty of extra room for add on accessories.

The following pre-configured packages are available for purchase from the AION ROBOTICS webstore [HERE]

Package Configuration Hardware Software
ArduPilot AutoPilot Control Pixhawk 2.1 ArduPilot
ArduROS Hybrid Control
  • Pixhawk 2.1
  • Jetson TX2
  • ArduPilot
  • ROS
ArduPilot Edition

The ArduPilot Edition leverages ArduPilot, the worlds leading Open Source autopilot software to manage platform tuning and basic autonomous control.

Detailed ArduPilot Info: [HERE]

Using a Ground Control Station such as [Mission Planner] users can easily build GPS based waypoint missions, view real time telemetry data, control servo’s and access all sensors without writing a single line of code. Users will also enjoy support for features like RTK and indoor positioning, obstacle avoidance, camera gimbal control and cant script advanced missions if needed.

For control hardware, the ArduPilot package utilizes a Pixhawk 2.1, the most advanced civilian grade autopilot module in the world. It boasts top notch features such as a triple redundant power supply, heat stabilized, triple redundant IMU, M8N GPS sensor and on board real time processor. Aion Robotics does not offer direct px4 support

Detailed Pixhawk 2.1 Info: [HERE]

ArduPilot Contents: Qty
Chassis 1
Wheels + Tires 4
Motors + Encoders 4
Motor Controller 1
Encoder Cables 2
Micro USB Port 1
FlySky i6S Transmitter 1
FlySky FS-IA6 Receiver 1
R/C Servo Cables 3
14.8V 5200Ah Smart Battery 1
Pixhawk 2.1 Autopilot 1
HERE M8N GPS Module 1
ArduROS Edition

The ArduROS Edition comes fully configured and “ready-to-code” out of the box.

In this configuration the vehicle is equipped with a Pixhawk 2.1 Autopilot module running ArduPilot and a Jetson TX2 running ROS.

You get all the easy to use features of the ArduPilot Edition UGV plus the ability to put ArduPilot in a “slave” mode utilizing ROS for advanced control and sensor integration projects.

Running the latest release of JetPack, you’ll have access to a full Ubuntu desktop and all the great features of linux. Whether developing Simultaneous Localization and Mapping applications, Deep Neural Networks, Object Detection and Tracking, the AIONio package will serve as an excellent foundation to get you going quickly.

Features:

  • TensorRT
  • cuDNN
  • VisonWorks/OpenCV
  • CUDA
  • Multimedia API
  • L4T
  • Development Tools

Detailed Jetson Module Info: [HERE]

Detailed JetPack Info: [HERE]

ArduROS Contents: Qty
Chassis 1
Wheels + Tires 4
Motors + Encoders 4
Motor Controller 1
Encoder Cables 2
Micro USB Port 1
USB 3.0 Port 1
RJ45 Ethernet Port 1
External Antenna Kit (2.4Ghz) 1
NVIDIA Jetson TX2 Dev Kit 1
FlySky i6S Transmitter 1
FlySky FS-IA6 Receiver 1
R/C Servo Cables 3
14.8V 5200Ah Smart Battery 1
Pixhawk 2.1 Autopilot 1
HERE M8N GPS Module 1

R1 User Guides

ArduPilot Package
Getting Started

Warning

* DANGER!! IMPORTANT!! MUST READ FIRST!! *

Use caution during setup and operation!

Due to the highly sensitive, open and modifiable nature of robotics systems please note that this system is sold “AS-IS” for Research and Development purposes.

AION ROBOTICS MAKES NO REPRESENTATION AND EXTENDS NO WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED. IN PARTICULAR, BUT WITHOUT LIMITATION, AION ROBOTICS MAKES NO REPRESENTATION AND EXTENDS NO WARRANTY CONCERNING WHETHER THIS PRODUCT IS FIT FOR ANY PARTICULAR PURPOSE.

All products go through a thorough quality assurance inspection before shipping. However, during the rigors of shipping, damage, loosening and/or shifting of bolts and other hardware can occur.

To ensure proper function of your system please complete a pre-operational inspection immediately upon opening the package. If you suspect damage, take pictures of both the damage and shipping box then notify the shipping carrier and AION ROBOTICS.

All vehicles are shipped from AION ROBOTICS fully preconfigured. You must only follow the calibration procedure and operational guides. All other materials are for informational purposes only.

Warning

When removing the top cover, always use extreme caution and remember to carefully disconnect cabling as required. Failure to do so will damage components.

Warning

The R1 is equipped with Brushed DC motors, all metal 40:1 gearboxes and bushing style bearings. Each motor is capable of 350 oz-in stall torque and rated at 14 watts. Operation outside of this limit will cause heat buildup, decrease motor life or damage the motors.

Warning

Due to the sensitive nature of electronics and robotics platforms in general, the R1 does not come with a warranty. ALWAYS use caution!

Pre-Operation Inspection

1. Damage Inspection:

Carefully inspect for damage.

  • Bent components
  • Abnormal or excessive wear
  • etc.

2. Hardware Inspection:

Fasteners and electrical connections.

  • Check for loose screws, bolts, nuts and electrical connectors.

Warning

Always disconnect battery before working on your rover!

Transmitter and Receiver

The included FrySky i6S transmitter and FS-X6B receiver come pre-bound from the factory but you will need to perform the following setup procedure to ensure proper functioning with AION ROBOTICS autopilot firmware configuration..

_images/FrySky_i6S.jpg
Function Channel
Throttle 3
Roll 1
Mode Selection 5
Save Waypoint 7
Arm/Disarm 8
  1. Install four “AA” batteries into the Transmitter. (Not included)
  2. Ensure switches SWA, SWB, SWC and SWD are in the UP position and Receiver is OFF
  3. Turn on Transmitter by pressing and holding both power buttons.
4. Setup – RX Output Mode

4.1. Press Setup button on the touch screen.

4.2. Select “SYS” or “SYSTEM” tab.

4.3. Select “Output mode”

4.4. Select “PPM” & “S.BUS”

4.5. Select back button

_images/OUTPUT_MODE.jpg
5. Setup – Sticks Mode

5.1. Under the “SYSTEM” tab, select “Sticks Mode”

5.2. Select M1 as pictured

5.3. Select back button

5.4. Select back button to return to Home Screen

_images/STICKS_MODE.jpg
6. Setup – “FLY MODE”

6.1. From Home Screen, press “FLY MODE”

6.2. Setup “MANUAL Mode” as pictured:

_images/SETUP_MANUAL.jpg

6.3. Flip SWB to the CENTER position

6.4. Setup “GUIDED” as pictured

_images/SETUP_GUIDED.jpg

6.5. Flip SWB to the LOWER position

6.6. Setup “AUTO” as pictured

_images/SETUP_AUTO.jpg
6.7. Press back button to return to Home Screen
  1. On the Home Screen, verify each “FLY MODE” by moving SWB from UPPER, CENTER and LOWER position. (MODE 1: MANUAL, MODE 2: GUIDED, MODE 3: AUTO)
8. Setup – Auxiliary Button (Used to store Waypoint)

8.1. Press Setup button on touch screen

8.2. Select “Aux. channels” under “FUNCTION” tab

8.3. Scroll to “Channel 7”

8.4. Select “Key 1” as pictured. (Left button on backside of controller)

8.5. Hit return button twice to return to home screen.

_images/AUX_7.jpg
9. Setup – Arm/Disarm Switch

9.1. Press Setup button on touch screen

9.2. Select “Aux. channels” under “FUNCTION” tab

9.3. Scroll to “Channel 8”

9.4. Select “SWD”.

9.5. Hit return button twice to return to home screen.

Autopilot Setup
1. Hardware Setup:
1.1. Install Autopilot module using the supplied screws and 4 holes located on the central chassis brace. (Ensure arrow is pointing toward the front of the rover)
_images/cube-arrow.jpg

1.2. Connect Servo cables

1.2.1. Autopilot “Main Out” Channel 1 -> Motor Controller “S1”

1.2.2. Autopilot “Main Out” Channel 3 -> Motor Controller “S2”

1.2.3. Autopilot RC IN -> FS-IA6B PPM/Channel 1

1.3. Install Power Brick Between the Male/Female XT60 connectors located on the Battery Harness

1.3.1. Using Power Cable, connect Power Brick -> Autopilot “Power1”

1.4. Connect Buzzer to “USB” port on Autopilot

1.5. Connect GPS plug to “CAN1” port

1.6. Telemetry Connection

  • If using [APSync] or AIONio to stream Mavlink over wifi, connect the companion computer to the “Telem2” port.
  • If using a long range telemetry radio such as RFD900, connect it to the “Telem1” port.

Note

  • Telem1 is “Serial 1” under firmware parameters and set at 921600 Baud. - Telem2 is “Serial 2” under firmware parameters and set at 921600 Baud.
_images/autopilot-wiring.jpg
2. Firmware Install:

Due to popularity, we recommend using Mission Planner for Windows or QGround Control works on Windows, Mac, IOS, Linux & Android.

  1. Parameter File

Tip

R1 UGVs come with firmware and parameters pre-installed and configured. This is for informational purposes only. Please skip to calibration.

1.1. R1 Parameter files and firmware can be obtained by customers by emailing info@aionrobotics.com
  1. Mission Planner GCS

2.1. Download & Install Mission Planner [HERE]

2.2. Open Mission Planner

2.3. Ensure Autopilot module is not powered

2.4. Connect your computer to the Autopilot module via Micro USB

2.5. Select “INITIAL SETUP” tab

2.6. Select “Install Firmware” (You must have internet connection)

2.7. Select “APM: Rover” vehicle type and follow flashing instructions

  1. Load Parameter File

3.1. Within Mission Planner, select the appropriate COM, Baud 9600 and click connect.

3.2. Select “CONFIG/TUNING” tab

3.3. Select “Full Parameter Tree”

3.4. Select “Load from file”

3.6. Select your parameter file

3.7. Select “Write Params”

3.8. Reboot the Pixhawk.

Motor Controller Setup
1. Hardware Setup: _images/controller-wiring.jpg _images/encoder-wiring.PNG

Note

Encoders are optional, they are not required for proper autopilot function.

2. Firmware Setup:

2.1. Download and install the “Ion Studio Setup Application” from [HERE] ..

2.2. Power the motor controller by plugging in and powering on the smart battery.

Note

The smart battery has a low current cutoff feature. To maintain minimum current requirements, the Pixhawk and GPS sensor must be plugged in.

2.3. Connect your computer to the motor controller via Micro USB port.

Note

The RoboClaw driver does not pull power from its USB port.

2.4. Open the Ion Studio Application and select “Connect Selected Unit”

2.5. Under the General Setting tab select “Control Mode”

2.5.1. Select “R/C Mode”

2.5.2. Place the R1 on a stand to ensure the tires can spin safely.

2.5.3. Under the PWM Settings” tab, slide the motor slider up to spin the motors forward. Check the encoder value boxes at the top of the screen to ensure the numbers are INCREASING in value.

Tip

If one or both numbers are counting backwards, simply reverse the effected encoders yellow & green wires.

2.5.4. Select “Device” tab

2.5.5. Select “Save Settings”

Note

For in-depth Firmware/Hardware setup guidelines please refer to the complete user manual located [HERE]

Wireless Telemetry Connection

If you purchased a bundle including a Wifi telemetry kit follow section 1. If using a companion computer to stream wireless telemetry via APSync follow section 2. If using a wireless radio set follow section 3.

1. Wifi Telemetry

1.1. Power on the vehicle and wait about 30 seconds.

1.2. On the device your GCS is installed on, go to your wireless settings and look for the vehicles wireless ID.

1.3. Connect to the network using password: “aionrobotics”

1.4. Open Mission Planner, select UDP in the upper right hand corner and click “Connect”

1.5. The GCS and Autopilot module will establish a connection.

Tip

You can also connect to the autopilot module directly from your internet browser via APweb. To do so, type: 10.0.1.128 into your browser address bar. (Limited functionality)

2. Long Range Radios
2.1. For telemetry radio options and setup instructions, see [HERE]
Calibration
1. Transmitter Calibration

1.1. Turn on Transmitter

1.2. Power on the R1 and connect to the GCS via wireless telemetry link.

1.3. Select the “FLIGHT DATA” tab and look in the HUD to ensure the vehicle is disarmed.

1.4. Select “INITIAL SETUP” tab

1.5. Select “Mandatory Hardware”

1.6. Select “Radio Calibration”

1.7. Select “Calibrate Radio” and follow instructions

Tip

Don’t forget to toggle your Fly Modes and Aux. Button to verify proper function.

1.8. Select the “FLIGHT MODES” tab and toggle “Fly Mode 1 - MANUAL, 2 – GUIDED and 3 – AUTO”. The corresponding mode should turn green upon activation.
2. Accel Calibration

2.1. Select “Accel Calibration” under the “INITIAL SETUP -> Mandatory Hardware” tabs.

2.2. Select “Calibrate Accel” and follow instructions

3. Compass Calibration

3.1. Select “Compass” under the “INITIAL SETUP -> Mandatory Hardware” tabs.

3.2. Find an outdoor area, clear of power lines and ferrous objects that will cause magnetic interference. (This includes metallic objects on your person)

3.3. Select “Start” in the “Onboard Mag Calibration” window and you will hear the Autopilot beep to signal calibration has started. (This will not work if the rover is Armed/Safety off)

3.4. To begin calibration, you must pick the rover up and spin it 360 degrees around each axis until the green bar next to “Mag 1” shows full and the GCS alerts you of a successful calibration.

Caution

Be careful not to drop the rover! You may want to enlist the help of another person!

Chassis Orientation Rotate
Level, Tires Down 360 Degrees
Left Side Up 360 Degrees
Right Side Up 360 Degrees
Front Up 360 Degrees
Front Down 360 Degrees
Level, Tires Up 360 Degrees
Operation

You should now be ready to test the R1!

Note

For GPS equipped rovers, upon booting the system, your rover will attempt to acquire a satellite lock as well as check magnetic health. When satellite lock is achieved, ArduPilot automatically marks its location as “Home” as can be seen in the “FLIGHT PLAN” tab in your GCS. (This can be moved manually)

Tip

To ensure stable operation and prevent error messages, do not operate your rover near tree’s or tall buildings/structures which can block LOS to GPS satellites, nor large metallic objects which can cause magnetic interference.

1. Booting The System

1.1. Turn on the Transmitter

1.2. Turn on the rover

1.3. The rover will boot “Disarmed” (Transmitter input is ignored)

1.4. Wait for the Autopilot tone to complete and achieve GPS lock (Signaled by Solid GREEN Status LED)

1.5. If equipped with wireless telemetry, connect your GCS to the autopilot.

2. Manual Control

2.1. Arm the vehicle by moving “SWD” into the down position.

2.2. The vehicle will beep and flashing Green LED will turn SOLID signally “ARMED”

2.3. Carefully use the transmitter to move the rover and verify that the direction of travel is correctly matched to the appropriate stick command.

3. Sample Autonomous Mission

3.1. While connected to the rover, select the “FLIGHT PLAN” tab within the GCS

3.2. If the GCS host device is connected to the internet, a map will display showing your rovers current position and “Home” position

3.3. Click on the map to draw a four waypoint mission as shown in the example:

_images/Tuning.PNG

3.4. For each waypoint you’ll see a corresponding command line populate under the “Waypoints” header

3.5. Click “Add Below” to add a new, blank, #5 Waypoint

3.6. Under “Waypoint 5” select the “Command” drop down list and choose “DO_JUMP”

3.7. In the box to the right, type “1” for Waypoint 1

3.8. In the following box type “-1” to designate the amount of times to repeat the mission

Note

The -1 input causes an endless loop condition. If you want the mission to repeat only 3 times, replace -1 with 3. If you do not add the Waypoint 5 command, the mission will end when it reaches waypoint 4.

3.9. Select “Write WPs” to write the mission to the Autopilot module

3.10. To start the mission, turn off the Safety Switch and toggle your transmitter to “Mode 3 – Auto”

Tip

Returning to “Mode 1 – Manual” will instantly stop the mission. Loss of transmitter signal will trigger a “Hold” failsafe condition until signal is returned.

Tip

When starting a mission, the rover will travel to each waypoint in consecutive order. Once it achieves Waypoint 4, the DO_JUMP command tells the rover to “Jump” back to “Waypoint 1” (signified in the box to the right) and to repeat this command as many times as listed in the following box.

Tuning Guide
_images/Tuning.PNG

The Parameter file available for download from Aion Robotics provides a stable, parameter configuration and tune. However, to achieve optimal performance, you will need to adjust the tuning parameters to your specific needs and conditions.

  1. Find a safe, open environment similar to your desired operating conditions and draw a rectangular, looped mission as illustrated in the previous “Sample Autonomous Mission” (Try to make the corners of the rectangle as perpendicular as possible)
  2. Start the mission and watch the rover as it navigates the course. The goal is to tune the rover so it makes each turn without overshooting the bearing to the next waypoint as pictured. If the rover overshoots (Turns too far), you must dampen the steering, if it undershoots (Turns to wide), you must increase the steering rate. Adjusting the Waypoint radius is also helpful.
ArduROS Package
Pre-Operation Inspection

1. Damage Inspection:

Carefully inspect for damage.

  • Bent components
  • Abnormal or excessive wear
  • etc.

2. Hardware Inspection:

Fasteners and electrical connections.

  • Check for loose screws, bolts, nuts and electrical connectors.

Warning

Always disconnect battery before working on your rover!

R6 Documentation

Model Specifications
_images/r6-render.jpg _images/r6-dimensions-inch.jpg _images/r6-dimensions-cm.jpg

New Offering - More information available soon

M Series Documentation

The M series represents Aion Robotics medium sized, heavy commercial platforms.

Under Construction

M4 Documentation

Under Construction

M6 Documentation

Under Construction

Autopilot Documentation

Available for purchase HERE.

Pixhawk 2.1 Autopilot Module

_images/pixhawk2-suite2.jpg

The Pixhawk 2.1 is the most advanced civilian grade autopilot module in the world.

Specifications:

  • Processor
    • 32-bit ARM Cortex M4 core with FPU
    • 168 Mhz/256 KB RAM/2 MB Flash
    • 32-bit failsafe co-processor
  • Sensors
    • Three redundant IMUs (accels, gyros and compass)
    • InvenSense MPU9250, ICM20948 and/or ICM20648 as first and third IMU (accel and gyro)
    • ST Micro L3GD20+LSM303D or InvenSense ICM2076xx as backup IMU (accel and gyro)
    • Two redundant MS5611 barometers
  • Power
    • Redundant power supply with automatic failover
    • Servo rail high-power (7 V) and high-current ready
    • All peripheral outputs over-current protected, all inputs ESD protected
  • Interfaces
    • 14x PWM servo outputs (8 from IO, 6 from FMU)
    • S.Bus servo output
    • R/C inputs for CPPM, Spektrum / DSM and S.Bus
    • Analogue / PWM RSSI input
    • 5x general purpose serial ports, 2 with full flow control
    • 2x I2C ports
    • SPI port (un-buffered, for short cables only not recommended for use)
    • 2x CAN Bus interface
    • 3x Analogue inputs (3.3V and 6.6V)
    • High-powered piezo buzzer driver (on expansion board)
    • High-power RGB LED (I2C driver compatible connected externally only)
    • Safety switch / LED
    • Optional carrier board for Intel Edison
  • Datasheet
  • Quick Start Guide
  • DF17 (Cube connector) Info

​Here & Here+ GPS

Companion Computer Documentation

_images/nvidia-logo.png

NVIDIA’s extremely powerful, energy efficient Jetson modules represent the most advanced computing platform for AI “at the edge”.

Jetson TX2 Hardware

Jetson AGX Xavier Hardware

Jetson AGX Xavier Software

Coming Soon

Sensor Documentation

Under Construction