Skip to content

Commit

Permalink
Update docs (#79)
Browse files Browse the repository at this point in the history
* Update docs for global planning

* Remove no longer needed package tf_relay

* Move odometry_conversion package to robot_interface

* Update robot interface docs

* Organize Robot docs
  • Loading branch information
andrewjong authored Oct 3, 2024
1 parent 2fef687 commit fddb6cd
Show file tree
Hide file tree
Showing 39 changed files with 509 additions and 499 deletions.
86 changes: 86 additions & 0 deletions docs/robot/autonomy/0_interface/index.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
# Interface

The interface defines the communication between the autonomy stack running on the onboard computer and the robot's control unit.
For example, for drones it converts the control commands from the autonomy stack into MAVLink messages for the flight controller.

==TODO: This is not our diagram, must replace.==
![Interface Diagram](https://404warehouse.net/wp-content/uploads/2016/08/softwareoverview.png?w=800)

The code is located under `AirStack/ros_ws/src/robot/autonomy/0_interface/`.

## Launch

Launch files are under `src/robot/autonomy/0_interface/interface_bringup/launch`.

The main launch command is `ros2 launch interface_bringup interface.launch.xml`.


## RobotInterface

Package `robot_interface` is a ROS2 node that interfaces with the robot's hardware.
The `RobotInterface` _gets robot state_ and forwards it to the autonomy stack,
and also _translates control commands_ from the autonomy stack into the command for the underlying hardware.
Note the base class is unimplemented.
Specific implementations should extend `class RobotInterface` in `robot_interface.hpp`, for example `class MAVROSInterface`.

### State
The `RobotInterface` class broadcasts the robot's pose as a TF2 transform.
It also publishes the robot's odometry as a `nav_msgs/Odometry` message to `$(arg robot_name)/0_interface/robot_0_interface/odometry`.

### Commands
The commands are variations of the two main command modes: Attitude control and Position control.
These are reflected in [MAVLink](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) and supported by both PX4 and [Ardupilot](https://ardupilot.org/dev/docs/copter-commands-in-guided-mode.html#movement-commands).

The Robot0_interface node subscribes to:

- `/$(arg robot_name)/interface/cmd_attitude_thrust` of type `mav_msgs/AttitudeThrust.msg`
- `/$(arg robot_name)/interface/cmd_rate_thrust` of type `mav_msgs/RateThrust.msg`
- `/$(arg robot_name)/interface/cmd_roll_pitch_yawrate_thrust` of type `mav_msgs/RollPitchYawrateThrust.msg`
- `/$(arg robot_name)/interface/cmd_torque_thrust` of type `mav_msgs/TorqueThrust.msg`
- `/$(arg robot_name)/interface/cmd_velocity` of type `geometry_msgs/TwistStamped.msg`
- `/$(arg robot_name)/interface/cmd_position` of type `geometry_msgs/PoseStamped.msg`

All messages are in the robot's body frame, except `velocity` and `position` which use the frame specified by the message header.

## MAVROSInterface
The available implementation in AirStack is called `MAVROSInterface` implemented in `mavros_interface.cpp`. It simply forwards the control commands to the Ascent flight controller (based on Ardupilot) using MAVROS.

## Custom Robot Interface
If you're using a different robot control unit with its own custom API, then you need to create an associated RobotInterface. Implementations should do the following:

### Broadcast State
Implementations of `RobotInterface` should obtain the robot's pose and broadcast it as a TF2 transform.

Should look something like:
```c++
// callback function triggered by some loop
void your_callback_function(){
// ...
geometry_msgs::msg::TransformStamped t;
// populate the transform, e.g.:
t.header = // some header
t.transform.translation.x = // some value
t.transform.translation.y = // some value
t.transform.translation.z = // some value
t.transform.rotation = // some quaternion
// Send the transformation
this->tf_broadcaster_->sendTransform(t);
// ...
}
```
==TODO: our code doesn't currently do it like this, it instead uses an external odometry_conversion node.==

### Override Command Handling
Should override all `virtual` functions in `robot_interface.hpp`:

- `cmd_attitude_thrust_callback`
- `cmd_rate_thrust_callback`
- `cmd_roll_pitch_yawrate_thrust_callback`
- `cmd_torque_thrust_callback`
- `cmd_velocity_callback`
- `cmd_position_callback`
- `request_control`
- `arm`
- `disarm`
- `is_armed`
- `has_control`
Binary file added docs/robot/autonomy/0_interface/mavlink.webp
Binary file not shown.
File renamed without changes.
9 changes: 9 additions & 0 deletions docs/robot/autonomy/2_perception/index.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Perception
These modules process raw sensor data into useful information for the robot. For example: for detecting obstacles, localizing the robot, and recognizing objects.

Perception modules typically output topics in image space or point cloud space. This information then gets aggregated into global and local world models later in the pipeline.

Common perception modules include:

- semantic segmentation
- VIO (Visual Inertial Odometry)
5 changes: 4 additions & 1 deletion docs/robot/autonomy/3_local/controls.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# Local Controls

## Trajectory Controller
The controller should publish control commands directly to topics defined by the [Robot Interface](../0_interface/robot_interface.md).

## Trajectory Controller

File renamed without changes.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
File renamed without changes.
73 changes: 61 additions & 12 deletions docs/robot/autonomy/4_global/planning.md
Original file line number Diff line number Diff line change
@@ -1,35 +1,73 @@
# Global Planning

![global_trajectory_diagram](global_trajectory.png)

Global planners output a high level, coarse trajectory for the robot to follow.

A trajectory is a spatial path plus a schedule.
A **trajectory** is a spatial path plus a schedule.
This means each waypoint in the trajectory has a time associated with it, indicating when the robot should reach that waypoint.
These timestamps are fed to the local planner to determine speed and acceleration.
These timestamps are fed to the local planner and controller to determine velocity and acceleration.

If a waypoint's header timestamp is empty, the local planner should assume there's no time constraint and follow the trajectory at its own pace.

The global planner should make a trajectory that is collision-free according to the global map.
However, avoiding fine obstacles is delegated to the local planner that operates at a faster rate.

## ROS Topics
We intend the global planners to be modular. _AirStack_ implements a basic Random Walk planner as a baseline.
Feel free to implement your own through the following interfaces.

## ROS Interfaces

Global planners are meant to be modules that can be swapped out easily.
They can be thought of as different high level behaviors for the robot to follow.
The Behavior Executive may run multiple global planners in parallel and choose the best plan for the current situation.

As such, the global planner should be implemented as a ROS2 action server that can be queried for a plan.
The Behavior Executive will then publish the best plan to `/$(arg robot_name)/global/trajectory` for the local planner to follow.

``` mermaid
sequenceDiagram
autonumber
Behavior Executive->>Global Planner: GetPlan.action: goal
loop Planning
Global Planner->>Behavior Executive: GetPlan.action: feedback
end
Global Planner-->>Behavior Executive: GetPlan.action: result (nav_msgs/Path)
Behavior Executive-->>Local Planner: /$ROBOT_NAME/global/trajectory (nav_msgs/Path)
```

### Actions Interface
The global planner should provide an action server for the topic `$(arg robot_name)/global_planner/plan` of message type `nav_msgs/GetPlan`.

Global Planner implementations should define a custom **GetPlan** action server and associated `GetPlan.action` message.
The action message may be defined with whatever input parameters necessary for the planner to generate a plan.
Your `GetPlan.action` _must_ return a `nav_msgs/Path` message.

An example `GetPlan.action` message is shown below.
```
# Define a goal
std_msgs/Duration timeout # maximum time to spend planning
geometry_msgs/Polygon bounds # boundary that the plan must stay within
---
# Define the result that will be published after the action execution ends.
{==nav_msgs/Path trajectory # REQUIRED FIELD==}
---
# Define a feedback message that will be published during action execution.
float32 percent_complete
```

### Subscribers
In general, the global planner needs access to components of the world model.

The most common one is the Occupancy Grids, which are published by the `map_server` node.
#### Goal
The goal defines the parameters that the global planner needs to generate a plan. All fields are optional.


### Publishers
#### Result
The global planner must have a return field `trajectory` of message type `nav_msgs/Path`.
`trajectory` defines high level waypoints to reach by a given time.

The global planner must publish a trajectory to the topic `$(arg robot_name)/global_planner/trajectory` of message type `nav_msgs/Path`.
The `nav_msgs/Path` message type contains a `header` field and `poses` field.

The header of the `nav_msgs/Path` message should contain the coordinate frame of the trajectory, and the timestamp should indicate when the trajectory was generated.
Each waypoint's header should contain the coordinate frame of the waypoint, and the timestamp should indicate when the waypoint should be reached.
- The top level header of `nav_msgs/Path` message should contain the coordinate frame of the trajectory, and its timestamp should indicate when the trajectory was published.
- Within the `poses` field, each `geometry_msgs/PoseStamped`'s header should contain a timestamp that indicates when that waypoint should be reached

```
nav_msgs/Path.msg
Expand All @@ -43,11 +81,22 @@ nav_msgs/Path.msg
- string frame_id: the coordinate frame of the waypoint
- geometry_msgs/Pose pose: the position and orientation of the waypoint
```
#### Feedback
All other fields are optional.


More info about ROS2 actions may be found in the official [tutorial](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Actions/Understanding-ROS2-Actions.html) and [design philosophy](https://design.ros2.org/articles/actions.html) documents.


### Subscribers
In general, the global planner needs to access components of the world model such as the map and drone state.

The most common map is Occupancy Grids that is published by {==TODO==} node.

The global planner can do whatever it wants internally.
The global planner can also access the robot's current state and expected state in the future. For example, if the global planner takes 20 seconds to plan a trajectory,
it can query where the robot expects to be in 20 seconds. This ROS2 service is available under {==TODO==}.

The global planner can do whatever it wants internally with this information.

## Example Planners

Expand Down
Empty file.
77 changes: 0 additions & 77 deletions docs/robot/autonomy/controls.md

This file was deleted.

12 changes: 11 additions & 1 deletion docs/robot/autonomy/index.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,13 @@
# Robot Autonomy
# Autonomy Modules

## Modules

- [0_interface](0_interface/index.md)
- [1_sensors](1_sensors/index.md)
- [2_perception](2_perception/README.md)
- [3_local](3_local/README.md)
- [4_global](4_global/README.md)
- [5_behavior](5_behavior/README.md)

## System Diagram
![AirStack System Diagram](airstack_system_diagram.png)
4 changes: 4 additions & 0 deletions docs/robot/index.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# Robot

## Launch Structure
Each high-level module has a `*_bringup` package that contains the launch files for that module. The launch files are located in the `launch` directory of the `*_bringup` package. The launch files are named `*.launch.(xml/yaml/py)` and can be launched with `ros2 launch <module_name>_bringup <module_name>.launch.(xml/yaml/py)`.
Empty file.
28 changes: 22 additions & 6 deletions mkdocs.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,17 @@ markdown_extensions:
pygments_lang_class: true
- pymdownx.inlinehilite
- pymdownx.snippets
- pymdownx.superfences
- pymdownx.magiclink
- pymdownx.critic
- pymdownx.caret
- pymdownx.keys
- pymdownx.mark
- pymdownx.tilde
- pymdownx.superfences:
custom_fences:
- name: mermaid
class: mermaid
format: !!python/name:pymdownx.superfences.fence_code_format
nav:
- Home: README.md
- Getting Started: getting_started.md
Expand All @@ -33,25 +42,32 @@ nav:
- CI/CD Pipeline: development/testing/ci_cd.md
- Contributing: development/contributing.md
- ROS Frame Conventions: development/frame_conventions.md
- Robot Autonomy:
- robot/autonomy/index.md
- Robot:
- robot/index.md
- Autonomy Modules:
- Interface:
- interface base class: robot/autonomy/0_interface/robot_interface.md
- robot/autonomy/index.md
- Interface:
- robot/autonomy/0_interface/index.md
- Sensors:
- robot/autonomy/1_sensors/sensors.md
- robot/autonomy/1_sensors/index.md
- Perception:
- robot/autonomy/2_perception/index.md
- robot/autonomy/2_perception/state_estimation.md
- Local:
- robot/autonomy/3_local/index.md
- World Model: robot/autonomy/3_local/world_model.md
- Planning: robot/autonomy/3_local/planning.md
- Controls: robot/autonomy/3_local/controls.md
- Global:
- robot/autonomy/4_global/index.md
- World Model: robot/autonomy/4_global/world_model.md
- Planning: robot/autonomy/4_global/planning.md
- Behavior:
- robot/autonomy/5_behavior/index.md
- Behavior Tree: robot/autonomy/5_behavior/behavior_tree.md
- Behavior Executive: robot/autonomy/5_behavior/behavior_executive.md
- Static Transforms:
- robot/static_transforms/index.md
- Logging:
- robot/logging/index.md
- Ground Control Station:
Expand Down
Loading

0 comments on commit fddb6cd

Please sign in to comment.