Skip to content

Commit

Permalink
Revert "Merge pull request #1023 from tier4/feat/pointcloud_delay"
Browse files Browse the repository at this point in the history
This reverts commit ff48453, reversing
changes made to 317da85.
  • Loading branch information
HansRobo committed Jul 26, 2023
1 parent ff48453 commit b7fd2de
Show file tree
Hide file tree
Showing 9 changed files with 45 additions and 299 deletions.
73 changes: 38 additions & 35 deletions docs/developer_guide/ConfiguringPerceptionTopics.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ where `<NAME>` and `<VALUE>` can be set to:
| `detectedObjectMissingProbability` | A `double` type value between `0.0` and `1.0` | `0.0` | Do not publish the perception topic with the given probability. |
| `detectedObjectPositionStandardDeviation` | A positive `double` type value | `0.0` | Randomize the positions of other vehicles included in the perception topic according to the given standard deviation. |
| `detectedObjectPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the perception topic by the specified number of seconds. |
| `pointcloudPublishingDelay` | A positive `double` type value | `0.0` | Delays the publication of the no_ground pointcloud by the specified number of seconds. |
| `randomSeed` | A positive `integer` type value | `0` | Specifies the seed value for the random number generator. |

These properties are not exclusive. In other words, multiple properties can be
Expand Down Expand Up @@ -129,39 +128,6 @@ not supported.
`"0.0"`, meaning no randomization.

**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.detectedObjectPositionStandardDeviation.yaml)** -

## Property `*PublishingDelay`
**Summary** - Delays the publication of the perception topic by the specified
number of seconds. There are two perception topic delay properties.

- `detectedObjectPublishingDelay` delays the publication of detected object.
- `pointcloudPublishingDelay` delays the publication of no_ground pointcloud.

**Purpose** - In a real vehicle, the perception topic is generated through the
processing of a sensing and perception module. However, in `scenario_simulator_v2`,
these processes are simplified. Detected objects are directly outputted as they
are from the simulator's objects, and no_ground pointcloud is the result of a
simple ray tracing. While this is suitable for testing planning and control modules
in an idealized environment, it does not account for the processing delays in
perception in a real vehicle. These properties can introduce an arbitrary delay
in the perception topic to simulate these real-world delays.

**Specification** - For each frame, if the current stamp exceeds the set time
from the topic's stamp, the topic is published, thereby implementing the delay.
This could result in a maximum error of 2/FPS. Also, the order of topics to be
published is guaranteed to be the same as when there is no delay.
Since the delay is set to the same value for each object, it is not possible to
delay only a specific object.

**Note** - This feature sets the delay from when the perception results are
obtained in `scenario_simulator_v2` to when they are published. Note that there
are other potential sources of delay, such as frame rates becoming unstable,
and delays in pub/sub.

**Default behavior** - If the property is not defined, the default value is
`"0.0"`, indicating no delay.

**[Example of detectedObjectPublishingDelay](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.detectedObjectPositionStandardDeviation.yaml)** -
```
ObjectController:
Controller:
Expand All @@ -174,7 +140,44 @@ and delays in pub/sub.
value: "3"
```

**[Example of pointcloudPublishingDelay](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.detectedObjectPublishingDelay.yaml)** -
## Property `detectedObjectPublishingDelay`

**Summary** - Delays the publication of the perception topic by the specified
number of seconds.

**Purpose** - Normally, Autoware reflects the surrounding situation in the
steering operation by processing the data in the order of the sensing module,
perception module, planning module, and vehicle driver. However, when not
connected with AWSIM, `scenario_simulator_v2` skips the sensing module and
perception module and directly generates the data of the perception result, and
sends it to the planning module. This behavior is desirable as a test of the
planning module, but on the other hand, there is a problem that the time until
the perception result is generated is unrealistically fast in response to
changes in the environment surrounding the vehicle. This property works around
this problem by setting an interval of the specified number of seconds between
`scenario_simulator_v2` generating a perception result and publishing it.

**Specification** - The property's value must be a positive real number. The
unit is seconds. It is an error if the value is negative. Since the delay is
set to the same value for each topic, it is not possible to delay only a
specific topic.

**Guarantee** - This delay setting ensures that `scenario_simulator_v2`
publishes the perception results in a consistent order. They are published
according to their original order. However, while `scenario_simulator_v2`
guarantees to publish in order, it does not guarantee that it reaches the
planning module in order. This is because the arrival order of topics in ROS 2
is not guaranteed.

**Note** - This feature only adjusts the interval between ssv2 generating a
perception result and publishing it. Note that there is another kind of delay
between when `scenario_simulator_v2` publishes the perception result and when
it reaches the planning module.

**Default behavior** - If the property is not specified, the default value is
`"0.0"`, meaning no delay.

**[Example](https://github.com/tier4/scenario_simulator_v2/blob/master/test_runner/scenario_test_runner/scenario/Property.detectedObjectPublishingDelay.yaml)** -
```
ObjectController:
Controller:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -245,8 +245,7 @@ class SimulatorCore
}());

if (controller.isUserDefinedController()) {
core->attachLidarSensor(
entity_ref, controller.properties.template get<Double>("pointcloudPublishingDelay"));
core->attachLidarSensor(entity_ref);

core->attachDetectionSensor([&]() {
simulation_api_schema::DetectionSensorConfiguration configuration;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <simulation_api_schema.pb.h>

#include <memory>
#include <queue>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <simple_sensor_simulator/sensor_simulation/lidar/raycaster.hpp>
Expand Down Expand Up @@ -57,8 +56,6 @@ class LidarSensor : public LidarSensorBase
{
const typename rclcpp::Publisher<T>::SharedPtr publisher_ptr_;

std::queue<std::pair<sensor_msgs::msg::PointCloud2, double>> queue_pointcloud_;

auto raycast(const std::vector<traffic_simulator_msgs::EntityStatus> &, const rclcpp::Time &)
-> T;

Expand All @@ -77,18 +74,10 @@ class LidarSensor : public LidarSensorBase
{
if (current_time - last_update_stamp_ - configuration_.scan_duration() >= -0.002) {
last_update_stamp_ = current_time;
queue_pointcloud_.push(std::make_pair(raycast(status, stamp), current_time));
publisher_ptr_->publish(raycast(status, stamp));
} else {
detected_objects_ = {};
}

if (
!queue_pointcloud_.empty() &&
current_time - queue_pointcloud_.front().second >= configuration_.lidar_sensor_delay()) {
const auto pointcloud = queue_pointcloud_.front().first;
queue_pointcloud_.pop();
publisher_ptr_->publish(pointcloud);
}
}

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ message LidarConfiguration {
repeated double vertical_angles = 3; // Vertical resolutions of the lidar. (unit : radian)
double scan_duration = 4; // Scan duration of the lidar. (unit: second)
string architecture_type = 5; // Autoware architecture type.
double lidar_sensor_delay = 6; // lidar sensor delay. (unit : second) It delays publishing timing.
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -236,8 +236,7 @@ class API

bool attachLidarSensor(const simulation_api_schema::LidarConfiguration &);
bool attachLidarSensor(
const std::string &, const double lidar_sensor_delay,
const helper::LidarType = traffic_simulator::helper::LidarType::VLP16);
const std::string &, const helper::LidarType = traffic_simulator::helper::LidarType::VLP16);

bool attachDetectionSensor(const simulation_api_schema::DetectionSensorConfiguration &);
bool attachDetectionSensor(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ enum class LidarType { VLP16, VLP32 };

const simulation_api_schema::LidarConfiguration constructLidarConfiguration(
const LidarType type, const std::string & entity, const std::string & architecture_type,
const double lidar_sensor_delay = 0, const double horizontal_resolution = 1.0 / 180.0 * M_PI);
const double horizontal_resolution = 1.0 / 180.0 * M_PI);

const simulation_api_schema::DetectionSensorConfiguration constructDetectionSensorConfiguration(
const std::string & entity, const std::string & architecture_type, const double update_duration,
Expand Down
7 changes: 2 additions & 5 deletions simulation/traffic_simulator/src/api/api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,13 +241,10 @@ bool API::attachLidarSensor(const simulation_api_schema::LidarConfiguration & li
}
}

bool API::attachLidarSensor(
const std::string & entity_name, const double lidar_sensor_delay,
const helper::LidarType lidar_type)
bool API::attachLidarSensor(const std::string & entity_name, const helper::LidarType lidar_type)
{
return attachLidarSensor(helper::constructLidarConfiguration(
lidar_type, entity_name, getParameter<std::string>("architecture_type", "awf/universe"),
lidar_sensor_delay));
lidar_type, entity_name, getParameter<std::string>("architecture_type", "awf/universe")));
}

bool API::updateTrafficLightsInSim()
Expand Down
3 changes: 1 addition & 2 deletions simulation/traffic_simulator/src/helper/helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,13 +95,12 @@ const simulation_api_schema::DetectionSensorConfiguration constructDetectionSens

const simulation_api_schema::LidarConfiguration constructLidarConfiguration(
const LidarType type, const std::string & entity, const std::string & architecture_type,
const double lidar_sensor_delay, const double horizontal_resolution)
const double horizontal_resolution)
{
simulation_api_schema::LidarConfiguration configuration;
configuration.set_horizontal_resolution(horizontal_resolution);
configuration.set_architecture_type(architecture_type);
configuration.set_entity(entity);
configuration.set_lidar_sensor_delay(lidar_sensor_delay);
switch (type) {
case LidarType::VLP16:
configuration.set_scan_duration(0.1);
Expand Down
Loading

0 comments on commit b7fd2de

Please sign in to comment.