Skip to content

Commit

Permalink
Add control messages and message-guidelines
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <mfc@leodrive.ai>
  • Loading branch information
M. Fatih Cırıt committed Apr 29, 2022
1 parent cf30f44 commit f3357a1
Show file tree
Hide file tree
Showing 10 changed files with 231 additions and 0 deletions.
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
# autoware_msgs

Before contributing, review [the message guidelines](./docs/message-guidelines.md).
26 changes: 26 additions & 0 deletions autoware_control_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
cmake_minimum_required(VERSION 3.5)
project(autoware_control_msgs)

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

set(msg_files
"msg/Control.msg"
"msg/ControlHorizon.msg"
"msg/Lateral.msg"
"msg/Longitudinal.msg")

set(msg_dependencies
builtin_interfaces)

rosidl_generate_interfaces(${PROJECT_NAME}
${msg_files}
DEPENDENCIES ${msg_dependencies}
ADD_LINTER_TESTS)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package()
13 changes: 13 additions & 0 deletions autoware_control_msgs/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# autoware_control_msgs

## Design

### Lateral.msg

### Longitudinal.msg

### Control.msg

Contains

### ControlHorizon.msg
6 changes: 6 additions & 0 deletions autoware_control_msgs/msg/Control.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Control message with lateral and longitudinal components

builtin_interfaces/Time stamp

Lateral lateral
Longitudinal longitudinal
9 changes: 9 additions & 0 deletions autoware_control_msgs/msg/ControlHorizon.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# Control messages for a predicted future horizon
#
# Control messages are ordered from near to far future (0 to N)
#
# To make it easier for controller to understand the time_steps

builtin_interfaces/Time stamp

Control[] controls
22 changes: 22 additions & 0 deletions autoware_control_msgs/msg/Lateral.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
# Lateral control message for Ackermann-style platforms
#
# Note regarding tires: If the platform has multiple steering tires, the commands
# given here are for a virtual tire at the average lateral position of the steering tires.
#
# Look up Ackermann Bicycle Model for more details
#
# Positive values represents left inclination (if forward)
# Negative values represents right inclination (if forward)
#
# Illustration: https://autowarefoundation.github.io/autoware-documentation/pr-79/design/autoware-interfaces/components/vehicle-dimensions/#vehicle-dimensions_1

builtin_interfaces/Time stamp

# Desired angle of the steering tire in rad (radians)
float32 steering_tire_angle

# Desired rate of change of the steering tire angle in rad/s
float32 steering_tire_rotation_rate;

# Controller has filled in the steering_tire_rotation_rate value
bool is_defined_steering_tire_rotation_rate;
23 changes: 23 additions & 0 deletions autoware_control_msgs/msg/Longitudinal.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Longitudinal control message
#
# Values are in the base_link frame in X axis
#
# Positive values represent forward motion (+X)
# Negative values represent backward motion (-X)

builtin_interfaces/Time stamp

# Desired vehicle velocity in in m/s
float32 velocity;

# Desired vehicle acceleration in m/s²
float32 acceleration;

# Desired vehicle jerk in m/s³
float32 jerk;

# Controller has filled in the acceleration value
bool is_defined_acceleration;

# Controller has filled in the jerk value
bool is_defined_jerk;
28 changes: 28 additions & 0 deletions autoware_control_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autoware_control_msgs</name>
<version>1.0.0</version>
<description>Autoware control messages package.</description>

<maintainer email="mfc@leodrive.ai">M. Fatih Cırıt</maintainer>
<maintainer email="opensource@apex.ai">Apex.AI, Inc.</maintainer>

<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>builtin_interfaces</depend>

<exec_depend>rosidl_default_runtime</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
1 change: 1 addition & 0 deletions build_depends.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
repositories:
101 changes: 101 additions & 0 deletions docs/message-guidelines.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
# Message guidelines

## Format

All messages should follow [ROS message description specification](https://docs.ros.org/en/galactic/Concepts/About-ROS-Interfaces.html#background).

The accepted formats are:

- `.msg`
- `.srv`
- `.action`

## Default units

All the fields by default have the following units depending on their types:

| type | default unit |
| -------------- | ------------- |
| distance | meter (m) |
| angle | radians (rad) |
| time | second (s) |
| speed | m/s |
| velocity | m/s |
| acceleration | m/s² |
| angular vel. | rad/s |
| angular accel. | rad/s² |

If the field in a message will have any of these default units, don't add any suffix or prefix denoting the type.

## Non-default units

For non-default units, use following suffixes:

| type | non-default unit | suffix |
| -------- | ---------------- | ------- |
| distance | nanometer | `_nm` |
| distance | micrometer | `_um` |
| distance | millimeter | `_mm` |
| distance | kilometer | `_km` |
| angle | degree (deg) | `_deg` |
| time | nanosecond | `_ns` |
| time | microsecond | `_us` |
| time | millisecond | `_ms` |
| time | minute | `_min` |
| time | hour (h) | `_hour` |
| velocity | km/h | `_kmph` |

## Message field types

For list of types supported by the ROS interfaces [see here](https://docs.ros.org/en/galactic/Concepts/About-ROS-Interfaces.html#field-types).

Also copied here for convenience:

| Message Field Type | C++ equivalent |
| ------------------ | ---------------- |
| `bool` | `bool` |
| `byte` | `uint8_t` |
| `char` | `char` |
| `float32` | `float` |
| `float64` | `double` |
| `int8` | `int8_t` |
| `uint8` | `uint8_t` |
| `int16` | `int16_t` |
| `uint16` | `uint16_t` |
| `int32` | `int32_t` |
| `uint32` | `uint32_t` |
| `int64` | `int64_t` |
| `uint64` | `uint64_t` |
| `string` | `std::string` |
| `wstring` | `std::u16string` |

## Comments

On top of the message, briefly explain what the message contains and/or what it is used for. See [sensor_msgs/msg/Imu.msg](https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/msg/Imu.msg#L1-L13) for an example.

If necessary, add line comments before the fields that explain the context and/or meaning.
For simple fields like `x, y, z, w` you might not need to add comments.

Even though it is not strictly checked, try not to pass 100 characters in a line.

_Example:_

```
# Number of times the vehicle performed an emergency brake
uint32 count_emergency_brake
# Seconds passed since the last emergency brake
uint64 duration
```

## Example usages

- Don't use unit suffixes for default types:
- Bad: `float32 path_length_m`
- Good: `float32 path_length`
- Don't prefix the units:
- Bad: `float32 kmph_velocity_vehicle`
- Good: `float32 velocity_vehicle_kmph`
- Use recommended suffixes if available:
- Bad: `float32 velocity_vehicle_km_h`
- Good: `float32 velocity_vehicle_kmph`

0 comments on commit f3357a1

Please sign in to comment.