Skip to content

Commit

Permalink
docs: update link style and fix typos (tier4#950)
Browse files Browse the repository at this point in the history
* feat(state_rviz_plugin): add GateMode and PathChangeApproval Button (tier4#894)

* feat(state_rviz_plugin): add GateMode and PathChangeApproval Button

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs: update link style

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* chore: fix link

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(map_tf_generator): accelerate the 'viewer' coordinate calculation (tier4#890)

* add random point sampling function to quickly calculate the 'viewer' coordinate

Signed-off-by: IshitaTakeshi <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenji Miyake <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs(obstacle_stop_planner): update documentation (tier4#880)

Signed-off-by: satoshi-ota <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs(tier4_traffic_light_rviz_plugin): update documentation (tier4#905)

Signed-off-by: satoshi-ota <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(accel_brake_map_calibrator): rviz panel type (tier4#895)

* fixed panel type

Signed-off-by: Mamoru Sobue <[email protected]>

* modified instruction for rosbag replay case

Signed-off-by: Mamoru Sobue <[email protected]>

* modified update_map_dir service name

Signed-off-by: Mamoru Sobue <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(behavior velocity planner): skipping emplace back stop reason if it is empty (tier4#898)

* skipping emplace back stop reason if it is empty

Signed-off-by: TakumiKozaka-T4 <[email protected]>

* add braces

Signed-off-by: TakumiKozaka-T4 <[email protected]>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Takagi, Isamu <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(behavior_path_planner): weakened noise filtering of drivable area (tier4#838)

* feat(behavior_path_planner): Weakened noise filtering of drivable area

Signed-off-by: Takayuki Murooka <[email protected]>

* fix lanelet's longitudinal disconnection

Signed-off-by: Takayuki Murooka <[email protected]>

* add comments of erode/dilate process

Signed-off-by: Takayuki Murooka <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* refactor(vehicle-cmd-gate): using namespace for msgs (tier4#913)

* refactor(vehicle-cmd-gate): using namespace for msgs

Signed-off-by: Takamasa Horibe <[email protected]>

* for clang

Signed-off-by: Takamasa Horibe <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(pose_initializer): introduce an array copy function (tier4#900)


Signed-off-by: IshitaTakeshi <[email protected]>

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat: add lidar point filter when debug (tier4#865)

* feat: add lidar point filter when debug

Signed-off-by: suchang <[email protected]>

* ci(pre-commit): autofix

Co-authored-by: suchang <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(component_interface_utils): add interface classes  (tier4#899)

* feat(component_interface_utils): add interface classes

Signed-off-by: Takagi, Isamu <[email protected]>

* feat(default_ad_api): apply the changes of interface utils

Signed-off-by: Takagi, Isamu <[email protected]>

* fix(component_interface_utils): remove old comment

Signed-off-by: Takagi, Isamu <[email protected]>

* fix(component_interface_utils): add client log

Signed-off-by: Takagi, Isamu <[email protected]>

* fix(component_interface_utils): remove unimplemented message

Signed-off-by: Takagi, Isamu <[email protected]>

* docs(component_interface_utils): add design policy

Signed-off-by: Takagi, Isamu <[email protected]>

* docs(component_interface_utils): add comment

Signed-off-by: Takagi, Isamu <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* refactor(vehicle_cmd_gate): change namespace in launch file (tier4#927)

Signed-off-by: Berkay <[email protected]>

Co-authored-by: Berkay <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat: visualize lane boundaries (tier4#923)

* feat: visualize lane boundaries

* fix: start_bound

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(system_monitor): fix truncation warning in strncpy (tier4#872)

* fix(system_monitor): fix truncation warning in strncpy

* Use std::string constructor to copy char array

* Fixed typo

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(behavior_velocity_planner.stopline): extend following and previous search range to avoid no collision (tier4#917)

* fix: extend following and previous search range to avoid no collision

* chore: add debug marker

* fix: simplify logic

* chore: update debug code

Signed-off-by: h-ohta <[email protected]>

* fix: delete space

* fix: some fix

* ci(pre-commit): autofix

* fix: delete debug code

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs(surround obstacle checker): update documentation (tier4#878)

* docs(surround_obstacle_checker): update pub/sub topics & params

Signed-off-by: satoshi-ota <[email protected]>

* docs(surround_obstacle_checker): remove unused files

Signed-off-by: satoshi-ota <[email protected]>

* docs(surround_obstacke_checker): update purpose

Signed-off-by: satoshi-ota <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(tier4_autoware_utils): add vehicle state checker (tier4#896)

* feat(tier4_autoware_utils): add vehicle state checker

Signed-off-by: satoshi-ota <[email protected]>

* fix(tier4_autoware_utils): use absolute value

Signed-off-by: satoshi-ota <[email protected]>

* feat(tier4_autoware_utils): divide into two classies

Signed-off-by: satoshi-ota <[email protected]>

* test(tier4_autoware_utils): add unit test for vehicle_state checker

Signed-off-by: satoshi-ota <[email protected]>

* fix(tier4_autoware_utils): impl class inheritance

Signed-off-by: satoshi-ota <[email protected]>

* docs(tier4_autoware_utils): add vehicle_state_checker document

Signed-off-by: satoshi-ota <[email protected]>

* fix(tier4_autoware_utils): into same loop

Signed-off-by: satoshi-ota <[email protected]>

* fix(tier4_autoware_utils): fix variables name

Signed-off-by: satoshi-ota <[email protected]>

* fix(tier4_autoware_utils): remove redundant codes

Signed-off-by: satoshi-ota <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(motion_velocity_smoother): fix overwriteStopPoint using backward point (tier4#816)

* fix(motion_velocity_smoother): fix overwriteStopPoint using backward point

Signed-off-by: kosuke55 <[email protected]>

* Modify overwriteStopPoint input and output

Signed-off-by: kosuke55 <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(obstacle_avoidance_planner): explicitly insert zero velocity (tier4#906)

* feat(obstacle_avoidance_planner) fix bug of stop line unalignment

Signed-off-by: Takayuki Murooka <[email protected]>

* fix bug of unsorted output points

Signed-off-by: Takayuki Murooka <[email protected]>

* move calcVelocity in node.cpp

Signed-off-by: Takayuki Murooka <[email protected]>

* fix build error

Signed-off-by: Takayuki Murooka <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(behavior_velocity): find occlusion more efficiently (tier4#829)

Signed-off-by: tanaka3 <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(system_monitor): add some smart information to diagnostics (tier4#708)

Signed-off-by: kk-inoue-esol <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(obstacle_avoidance_planner): dealt with close lane change (tier4#921)

* feat(obstacle_avoidance_planner): dealt with close lane change

Signed-off-by: Takayuki Murooka <[email protected]>

* fix bug of right lane change

Signed-off-by: Takayuki Murooka <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(obstacle_avoidance_planner): some fix for narrow driving (tier4#916)

* use car like constraints in mpt

* use not widest bounds for the first bounds

Signed-off-by: Takayuki Murooka <[email protected]>

* organized params

Signed-off-by: Takayuki Murooka <[email protected]>

* fix format

Signed-off-by: Takayuki Murooka <[email protected]>

* prepare rear_drive and uniform_circle constraints

Signed-off-by: Takayuki Murooka <[email protected]>

* fix param callback

Signed-off-by: Takayuki Murooka <[email protected]>

* update config

Signed-off-by: Takayuki Murooka <[email protected]>

* remove unnecessary files

Signed-off-by: Takayuki Murooka <[email protected]>

* update tier4_planning_launch params

Signed-off-by: Takayuki Murooka <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* chore(obstacle_avoidance_planner): removed obsolete obstacle_avoidance_planner doc in Japanese (tier4#919)

Signed-off-by: Takayuki Murooka <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check (tier4#932)

* chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check

* feat: use marker helper

Signed-off-by: h-ohta <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(map_loader): visualize center line by points (tier4#931)

* feat: visualize center line points

* fix: delete space

* feat: visualize center line by arrow

* revert insertMarkerArray

* fix: delete space

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat: add RTC interface (tier4#765)

* feature(rtc_interface): add files

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): implement functions

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): reimprement functions to use CooperateCommands and write README.md

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): fix README

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): add getModuleType()

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): fix definition of constructor

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): fix time stamp

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): fix README

Signed-off-by: Fumiya Watanabe <[email protected]>

* feature(rtc_interface): add isRegistered and clearCooperateStatus

Signed-off-by: Fumiya Watanabe <[email protected]>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* chore: sync files (tier4#911)

Signed-off-by: GitHub <[email protected]>

Co-authored-by: kenji-miyake <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: replace boost::mutex::scoped_lock to std::scoped_lock (tier4#907)

* fix: replace boost::mutex::scoped_lock to std::scoped_lock

* fix: replace boost::mutex to std::mutex

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node (tier4#885)

* feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node

Signed-off-by: Kaan Colak <[email protected]>

* feat(tensorrt_yolo): update arg

Signed-off-by: Kaan Colak <[email protected]>

Co-authored-by: Kaan Colak <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner (tier4#887)

* feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner

* Update launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml

Co-authored-by: taikitanaka3 <[email protected]>

* feat: add param.yaml in behavior_velocity_planner package

* some fix

Co-authored-by: taikitanaka3 <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader (tier4#942)

* fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader

Signed-off-by: RyuYamamoto <[email protected]>

* fix(map_loader): remove c_str

Signed-off-by: RyuYamamoto <[email protected]>

* fix(map_loader): replace c_str to string

Signed-off-by: RyuYamamoto <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: relative link

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: relative links

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: relative links

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: relative links

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix: typo

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* fix relative links

Signed-off-by: Kenji Miyake <[email protected]>
Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs: ignore rare unknown words

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* docs: ignore unknown words one by one

Signed-off-by: Shumpei Wakabayashi <[email protected]>

* ci(pre-commit): autofix

Co-authored-by: Hiroki OTA <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Takeshi Ishita <[email protected]>
Co-authored-by: Kenji Miyake <[email protected]>
Co-authored-by: Satoshi OTA <[email protected]>
Co-authored-by: Mamoru Sobue <[email protected]>
Co-authored-by: TakumiKozaka-T4 <[email protected]>
Co-authored-by: Takagi, Isamu <[email protected]>
Co-authored-by: Takayuki Murooka <[email protected]>
Co-authored-by: Takamasa Horibe <[email protected]>
Co-authored-by: storrrrrrrrm <[email protected]>
Co-authored-by: suchang <[email protected]>
Co-authored-by: Berkay <[email protected]>
Co-authored-by: Berkay <[email protected]>
Co-authored-by: ito-san <[email protected]>
Co-authored-by: Kosuke Takeuchi <[email protected]>
Co-authored-by: taikitanaka3 <[email protected]>
Co-authored-by: kk-inoue-esol <[email protected]>
Co-authored-by: Fumiya Watanabe <[email protected]>
Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com>
Co-authored-by: kenji-miyake <[email protected]>
Co-authored-by: RyuYamamoto <[email protected]>
Co-authored-by: Kaan Çolak <[email protected]>
Co-authored-by: Kaan Colak <[email protected]>
Co-authored-by: Kenji Miyake <[email protected]>
  • Loading branch information
26 people authored and boyali committed Oct 19, 2022
1 parent f0696ec commit 44880b5
Show file tree
Hide file tree
Showing 19 changed files with 35 additions and 31 deletions.
2 changes: 1 addition & 1 deletion common/autoware_auto_common/design/comparisons.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Comparisons {#helper-comparisons}
# Comparisons

The `float_comparisons.hpp` library is a simple set of functions for performing approximate numerical comparisons.
There are separate functions for performing comparisons using absolute bounds and relative bounds. Absolute comparison checks are prefixed with `abs_` and relative checks are prefixed with `rel_`.
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_geometry/design/interval.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Interval {#geometry-interval}
# Interval

The interval is a standard 1D real-valued interval.
The class implements a representation and operations on the interval type and guarantees interval validity on construction.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# 2D Convex Polygon Intersection {#convex-polygon-intersection-2d}
# 2D Convex Polygon Intersection

Two convex polygon's intersection can be visualized on the image below as the blue area:

Expand Down
6 changes: 4 additions & 2 deletions common/autoware_auto_geometry/design/spatial-hash-design.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Spatial Hash {#geometry-spatial-hash}
# Spatial Hash

The spatial hash is a data structure designed for efficient fixed-radius near-neighbor queries in
low dimensions.
Expand Down Expand Up @@ -35,9 +35,11 @@ The spatial hash works as follows:
Under the hood, an `std::unordered_multimap` is used, where the key is a bin/voxel index.
The bin size was computed to be the same as the lookup distance.

<!-- cspell:ignore CRTP -->

In addition, this data structure can support 2D or 3D queries. This is determined during
configuration, and baked into the data structure via the configuration class. The purpose of
this was to avoid if statements in tight loops. The configuration class specializations themself
this was to avoid if statements in tight loops. The configuration class specializations themselves
use CRTP (Curiously Recurring Template Patterns) to do "static polymorphism", and avoid
a dispatching call.

Expand Down
8 changes: 4 additions & 4 deletions common/autoware_auto_tf2/design/autoware-auto-tf2-design.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# autoware_auto_tf2 {#autoware-auto-tf2-design}
# autoware_auto_tf2

This is the design document for the `autoware_auto_tf2` package.

Expand Down Expand Up @@ -110,7 +110,7 @@ inline void doTransform(
const geometry_msgs::msg::TransformStamped & transform)
```
- `Quarternion32` (`autoware_auto_msgs`)
- `Quaternion32` (`autoware_auto_msgs`)
```cpp
inline void doTransform(
Expand Down Expand Up @@ -169,15 +169,15 @@ inline std::string getFrameId(const BoundingBoxArray & t)
## Challenges
- `tf2_geometry_msgs` does not implement `doTransform` for any non-stamped datatypes, but it is
- `tf2_geometry_msgs` does not implement `doTransform` for any non-stamped data types, but it is
possible with the same function template. It is needed when transforming sub-data, with main data
that does have a stamp and can call doTransform on the sub-data with the same transform. Is this a useful upstream contribution?
- `tf2_geometry_msgs` does not have `Point`, `Point32`, does not seem it needs one, also the
implementation of non-standard `toMsg` would not help the convert.
- `BoundingBox` uses 32-bit float like `Quaternion32` and `Point32` to save space, as they are used
repeatedly in `BoundingBoxArray`. While transforming is it better to convert to 64-bit `Quaternion`,
`Point`, or `PoseStamped`, to re-use existing implementation of `doTransform`, or does it need to be
implemented? Templatization may not be simple.
implemented? It may not be simple to template.
<!-- # Related issues -->
<!-- Required -->
2 changes: 1 addition & 1 deletion common/autoware_testing/design/autoware_testing-design.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# autoware_testing {#autoware_testing-package-design}
# autoware_testing

This is the design document for the `autoware_testing` package.

Expand Down
2 changes: 1 addition & 1 deletion common/fake_test_node/design/fake_test_node-design.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Fake Test Node {#fake-test-node-design}
# Fake Test Node

## What this package provides

Expand Down
2 changes: 1 addition & 1 deletion common/osqp_interface/design/osqp_interface-design.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Interface for the OSQP library {#osqp_interface-package-design}
# Interface for the OSQP library

This is the design document for the `osqp_interface` package.

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# vehicle_constants_manager {#vehicle-constants-manager-package-design}
# vehicle_constants_manager

This is the design document for the `vehicle_constants_manager` package.

Expand Down Expand Up @@ -83,7 +83,7 @@ vehicle:
inertia_yaw_kg_m_2:
```
## Inputs / Outputs / API {#vehicle-constants-manager-package-design-inputs}
## Inputs / Outputs / API
<!-- Required -->
<!-- Things to consider:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Trajectory Follower {#trajectory_follower-package-design}
# Trajectory Follower

This is the design document for the `trajectory_follower` package.

Expand All @@ -12,9 +12,9 @@ This package provides the library code used by the nodes of the `trajectory_foll
Mainly, it implements two algorithms:

- Model-Predictive Control (MPC) for the computation of lateral steering commands.
- @subpage trajectory_follower-mpc-design
- [trajectory_follower-mpc-design](trajectory_follower-mpc-design.md)
- PID control for the computation of velocity and acceleration commands.
- @subpage trajectory_follower-pid-design
- [trajectory_follower-pid-design](trajectory_follower-pid-design.md)

## Related issues

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# MPC (Trajectory Follower) {#trajectory_follower-mpc-design}
# MPC (Trajectory Follower)

This is the design document for the MPC implemented in the `trajectory_follower` package.

Expand Down Expand Up @@ -34,7 +34,7 @@ Different vehicle models are implemented:

The `kinematics` model is being used by default. Please see the reference [1] for more details.

For the optimization, a Quadratric Programming (QP) solver is used
For the optimization, a Quadratic Programming (QP) solver is used
with two options are currently implemented:

- `unconstraint` : use least square method to solve unconstraint QP with eigen.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# PID (Trajectory Follower) {#trajectory_follower-pid-design}
# PID (Trajectory Follower)

This is the design document for the PID implemented in the `trajectory_follower` package.

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Lateral Controller {#lateral-controller-design}
# Lateral Controller

This is the design document for the lateral controller node
in the `trajectory_follower_nodes` package.
Expand All @@ -23,7 +23,7 @@ The MPC uses a model of the vehicle to simulate the trajectory resulting from th
The optimization of the control command is formulated as a Quadratic Program (QP).

These functionalities are implemented in the `trajectory_follower` package
(see @subpage trajectory_follower-mpc-design)
(see [trajectory_follower-mpc-design](../../trajectory_follower/design/trajectory_follower-mpc-design.md#mpc-trajectory-follower))

### Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Lateral/Longitudinal Control Muxer {#latlon-muxer-design}
# Lateral/Longitudinal Control Muxer

## Purpose

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Longitudinal Controller {#longitudinal-controller-design}
# Longitudinal Controller

## Purpose / Use cases

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Trajectory Follower Nodes {#trajectory_follower_nodes-package-design}
# Trajectory Follower Nodes

## Purpose

Expand All @@ -8,12 +8,12 @@ Generate control commands to follow a given Trajectory.

This functionality is decomposed into three nodes.

- @subpage lateral-controller-design : generates lateral control messages.
- @subpage longitudinal-controller-design : generates longitudinal control messages.
- @subpage latlon-muxer-design : combines the lateral and longitudinal control commands
- [lateral-controller-design](lateral_controller-design.md) : generates lateral control messages.
- [longitudinal-controller-design](longitudinal_controller-design.md) : generates longitudinal control messages.
- [latlon-muxer-design](latlon_muxer-design.md) : combines the lateral and longitudinal control commands
into a single control command.

Core functionalities are implemented in the @subpage trajectory_follower-package-design package.
Core functionalities are implemented in the [trajectory_follower](../../trajectory_follower/design/trajectory_follower-design.md#trajectory-follower) package.

@image html images/trajectory_follower-diagram.png "Overview of the Trajectory Follower package"

Expand Down
2 changes: 2 additions & 0 deletions perception/tensorrt_yolo/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@ This package detects 2D bounding boxes for target objects e.g., cars, trucks, bi

### Cite

<!-- cspell:ignore Redmon, Farhadi, Bochkovskiy, Jocher, ultralytics, Roboflow, Zenodo -->

yolov3

Redmon, J., & Farhadi, A. (2018). Yolov3: An incremental improvement. arXiv preprint arXiv:1804.02767.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ obstacle that can run out from occlusion should have free space until intersecti

##### Possible Collision

obstacle that can run out from occlusion is interruped by moving vehicle.
obstacle that can run out from occlusion is interrupted by moving vehicle.
![brief](./docs/occlusion_spot/raycast_shadow.drawio.svg)

#### Module Parameters
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# simple_planning_simulator {#simple_planning_simulator-package-design}
# simple_planning_simulator

## Purpose / Use cases

Expand Down

0 comments on commit 44880b5

Please sign in to comment.