Skip to content

Commit

Permalink
separate stamp and control_time, fill in README.md
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 Jun 6, 2022
1 parent 8c5e4f5 commit 35dbbe8
Show file tree
Hide file tree
Showing 5 changed files with 53 additions and 3 deletions.
30 changes: 30 additions & 0 deletions autoware_control_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,38 @@ Vehicle dimensions and axes: <https://autowarefoundation.github.io/autoware-docu

### Lateral.msg

Defines a lateral control command message with a timestamp.

The message conveys the expectation for vehicle's lateral state to be in the given configuration in the time point: `control_time`.

- The field `steering_tire_angle` is required.
- The field `steering_tire_rotation_rate` is optional but may be required by some nodes.
- If this field is used, `is_defined_steering_tire_rotation_rate` must be set `true`.

### Longitudinal.msg

Defines a longitudinal control command message with a timestamp.

The message conveys the expectation for vehicle's longitudinal state to be in the given configuration in the time point: `control_time`.

- The field `velocity` is required.
- The field `acceleration` is optional but may be required by some nodes.
- If this field is used, `is_defined_acceleration` must be set `true`.
- The field `jerk` is optional but may be required by some nodes.
- If this field is used, `is_defined_jerk` must be set `true`.

### Control.msg

Defines a control command message, combining `Lateral.msg` and `Longitudinal.msg`.

The message conveys the expectation for vehicle's combined control state to be in the given configuration in the time point: `control_time`.

If the `control_time` is defined, the `control_time` field in the `lateral` and `longitudinal` fields are ignored.

### ControlHorizon.msg

Defines a control commands array calculated for a future horizon.

- Control messages are ordered from near to far future `[0 to N)` with `time_step_ms` increments.
- First element of the array contains the control signals at the `control_time` of this message.
- The `control_time` field in each element of the controls array can be ignored.
7 changes: 7 additions & 0 deletions autoware_control_msgs/msg/Control.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,13 @@
# Control message with lateral and longitudinal components

# Time this message was created
builtin_interfaces/Time stamp

# Time this configuration state is expected to be achieved in (optional)
builtin_interfaces/Time control_time

# Lateral control command
Lateral lateral

# Longitudinal control command
Longitudinal longitudinal
11 changes: 8 additions & 3 deletions autoware_control_msgs/msg/ControlHorizon.msg
Original file line number Diff line number Diff line change
@@ -1,13 +1,18 @@
# Control messages predicted for a future horizon
# Control messages calculated for a future horizon
#
# Control messages are ordered from near to far future [0 to N) with time_step_ms increments.
#
# First element of the array contains the control signals at the stamp of this message.
# First element of the array contains the control signals at the control_time of this message.
#
# The stamps in the controls array can be ignored.
# The control_time field in each element of the controls array can be ignored.

# Time this message was created
builtin_interfaces/Time stamp

# Time when controls[0] configuration state is expected to be achieved in
builtin_interfaces/Time control_time

# Time difference between consecutive elements of the controls array in milliseconds
float32 time_step_ms

Control[] controls
4 changes: 4 additions & 0 deletions autoware_control_msgs/msg/Lateral.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,12 @@
# Positive values represents left inclination (if forward)
# Negative values represents right inclination (if forward)

# Time this message was created
builtin_interfaces/Time stamp

# Time this configuration state is expected to be achieved in (optional)
builtin_interfaces/Time control_time

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

Expand Down
4 changes: 4 additions & 0 deletions autoware_control_msgs/msg/Longitudinal.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,12 @@
# Positive values represent forward motion (+X)
# Negative values represent backward motion (-X)

# Time this message was created
builtin_interfaces/Time stamp

# Time this configuration state is expected to be achieved in (optional)
builtin_interfaces/Time control_time

# Desired vehicle velocity in in m/s
float32 velocity

Expand Down

0 comments on commit 35dbbe8

Please sign in to comment.