Skip to content
This repository has been archived by the owner on Mar 17, 2021. It is now read-only.

Traxxas Stampede Documentation #169

Merged
merged 5 commits into from
Jun 7, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file not shown.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added assets/gazebo/rover.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
1 change: 1 addition & 0 deletions en/SUMMARY.md
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@
* [VTOL Testing](airframes_vtol/testing.md)
* [TBS Caipiroshka](airframes_vtol/caipiroshka.md)
* [Boats, Submarines, Blimps, Rovers](airframes_experimental/README.md)
* [Traxxas Sampede](airframes_experimental/traxxas_stampede.md)
* [Companion Computers](companion_computer/README.md)
* [Pixhawk family companion](companion_computer/pixhawk_companion.md)
* [Robotics using DroneKit](dronekit/README.md)
Expand Down
6 changes: 4 additions & 2 deletions en/airframes_experimental/README.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
# Experimental Aircraft and General Robots
# Experimental Aircraft, UGVs and General Robots

Work in progress
The [PX4 Flight Stack](../concept/flight_stack.md) is currently trying to expand the capabilities to other platforms such as Experimental Aircrafts, UGVs (Unmanned Ground Vehicles) and general robots.

Currently an UGV demo has been carried out, please refer to the [subsection](./traxxas_stampede.md) for more information.
120 changes: 120 additions & 0 deletions en/airframes_experimental/traxxas_stampede.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
# Traxxas Stampede VXL

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great to have a short paragraph here about why this vehicle selected and what the conversion to autopilot required - e.g. I assume because this is a nice big frame at a good price point. From your diagram all you needed to do was create a mount for the autopilot electronics.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great idea! It was chosen mostly because Traxxas RC cars are very popular (see JetsonHacks, MIT racecar just to name two) but I'll add the reasoning here.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Excellent. I might tidy this a little once you're merged.

This vehicle was chosen to understand how a Pixhawk could be used for wheeled platforms. We chose to use a Traxxas vehicle as they are very popular and it is a very strong brand in the RC community. The idea was to develop a platform that allows for easy control of wheeled UGVs with an autopilot.

{% youtube %}https://youtu.be/N3HvSKS3nCw{% endyoutube %}

![Traxxas Stampede VXL](../../assets/airframes/experimental/stampede/stampede.jpg)

## Parts List

* [Traxxas Stampede](https://traxxas.com/products/models/electric/stampede-vxl-tsm) All of this is used except for the top plastic cover.
* [Pixhawk Mini](https://store.3dr.com/products/3dr-pixhawk)
* [Power Module](https://store.3dr.com/products/10s-power-module)
* [Telemetry Module (EU)](https://store.3dr.com/products/433-mhz-telemetry-radio) US version available in the website
* [Spektrum Dxe Controller](http://www.spektrumrc.com/Products/Default.aspx?ProdId=SPM1000) or other PX4-compatible remotes
* [Spektrum Quad Race Serial Receiver w/Diversity](http://www.spektrumrc.com/Products/Default.aspx?ProdID=SPM4648)
* [PX4Flow](https://pixhawk.org/modules/px4flow)


## Assembly

The assembly consists of a wooden frame on which all the autopilot parts were attached. Tests showed that a better vibration insulation should be used, especially for the Pixhawk and the Flow module.

![Stampede Chassis](../../assets/airframes/experimental/stampede/stampede_chassis.jpg)

![Wooden Panel Top](../../assets/airframes/experimental/stampede/panel_top.jpg)

![Wooden Panel Bottom](../../assets/airframes/experimental/stampede/panel_bottom.jpg)

![Traxxas Stampede Final Assembly](../../assets/airframes/experimental/stampede/final_assembly.jpg)

![Side View Final Assembly](../../assets/airframes/experimental/stampede/final_side.jpg)

![Wodden panel fixture](../../assets/airframes/experimental/stampede/mounting_detail.jpg)

For this particular mounting we chose to use the clip supplied with the rover to attach the upper plate. For this, two supports were 3D printed. The CAD files are provided [here](../../assets/airframes/experimental/stampede/plane_holders.zip).

> **Warning** It is **HIGHLY RECOMMENDED** to set the ESC in training mode (see Traxxas Stampede Manual) so to reduce the power to 50%.


## Output connections

| PWM Output | Rate | Actuator |
| -- | -- | -- |
| MAIN1 | 50 Hz | Not connected |
| MAIN2 | 50 Hz | Steering servo |
| MAIN3 | 50 Hz | Not Connected |
| MAIN4 | 50 Hz | ESC input |
| MAIN5 | 50 Hz | Not Connected |
| MAIN6 | 50 Hz | Not Connected |
| MAIN7 | 50 Hz | Not Connected |
| MAIN8 | 50 Hz | Not Connected |

## Simulation

To test the algorithms, a simulation was used. This can be ran by running

```sh
make posix gazebo-rover
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this really all you need to do? Perhaps link to gazebo setup docs here ... and also add a section on this frame there?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comes from #6615. I'll add it in that section in the next commit, thanks!

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great. Please add a link to the gazebo docs here too.

```

from the Firmware folder. More details on how to do it can be found in section [Gazebo Simulation](../simulation/gazebo.md).

## Usage
At the current time, PX4 only supports MISSION and MANUAL modes when a RC remote is connected. To use the mission mode, first upload a new mission to the vehicle with QGC. Then, BEFORE ARMING, select `MISSION` and then arm.

> **Warning** It is **_VERY IMPORTANT_** to do a mission composed **_ONLY_** by normal waypoints (i.e. **_NO TAKEOFF WAYPOINTS_**) and it is crucial to **_SET THE WAYPOINT HEIGHT OF EVERY WAYPOINT TO 0_** for a correct execution. Failing to do so will cause the rover to continuously spin around a waypoint.


A correct mission setup looks as follows

![mission](../../assets/airframes/experimental/stampede/correct_mission.jpg)

Since at the current state of development there is no obstacle avoidance, it is highly recommended to test missions in the simulator first to get acquainted with the software usage.


## Building the firmware
To build the firmware it is necessary to use the terminal (QGC is not supported yet). This can be done by following the instructions in [Building the Code section](../setup/building_px4.md) and uploading by running

```sh
cd ~/src/Firmware
make px4fmu-v2_default upload
```

## Parameters

The current software provides an attitude controller and a position controller. These build on top of the fixed wing framework to move an Ackerman steered vehicle following GPS coordinates (real or fake). In order to this, 2 PIDs were implemented, one for the steering and the other for the speed.
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps be a bit more declarative - tell users that they need to set these parameters manually, and link to instructions in QGC for setting parameters

These can be started by setting the following general parameters, which can be set with QGC (instructions [here](https://docs.qgroundcontrol.com/en/SetupView/Parameters.html)):
* SYS_AUTOSTART 50002
* MAV_TYPE 10
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I see that the 'airframe' config already sets the MAV_TYPE and the tuning params. So it's not necessary to add them here. But I think it's useful to describe which params can be tuned & how.

* MIS_LTRMIN_ALT 0.01
* MIS_TAKEOFF_ALT 0.01

This allows to start the Pixhawk configured for the Traxxas Stampede VXL. Then, the steering controller can be tuned with these parameters:
* GND_WR_D 0.1
* GND_WR_I 0.01
* GND_WR_IMAX 0.1
* GND_WR_P 1.5

The closed loop speed control can be enabled by setting
* GND_SP_CTRL_MODE 1

which uses the second PID to control the speed with the following parameters:
* GND_SPEED_D 5
* GND_SPEED_I 0.01
* GND_SPEED_IMAX 0.5
* GND_SPEED_P 2.0
* GND_SPEED_THR_SC 0.1
* GND_SPEED_TRIM 4

If the closed loop is enabled the speed controller will take the GND_SPEED_TRIM as a target speed and will attempt to track it. If, on the other hand, GND_SP_CTRL_MODE is set to 0 then the speed controller will turn to a safe open loop setting of the throttle, controlled by these parameters:
* GND_THR_CRUISE 0.1
* GND_THR_IDLE 0
* GND_THR_MAX 0.5
* GND_THR_MIN 0

Then, general navigation parameters can be tuned for a better usage:
* GND_L1_DIST 3
* NAV_ACC_RAD 0.5

9 changes: 9 additions & 0 deletions en/simulation/gazebo.md
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,15 @@ make posix_sitl_default gazebo_tailsitter

![](../../assets/gazebo/tailsitter.png)

### Ackerman vehicle

```sh
make posix gazebo_rover
```

![](../../assets/gazebo/rover.png)


## Change World

The current default world is the iris.wold located in the directory [worlds](https://github.com/PX4/sitl_gazebo/tree/367ab1bf55772c9e51f029f34c74d318833eac5b/worlds). The default surrounding in the iris.world uses a heightmap as ground. This ground can cause difficulty when using a distance sensor. If there are unexpected results with that heightmap, it is recommended to change the model in iris.model from uneven_ground to asphalt_plane.
Expand Down