diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp index eb477a9d661..f5545a0d9d4 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/detection_sensor/detection_sensor.hpp @@ -89,7 +89,7 @@ class DetectionSensor : public DetectionSensorBase auto update( const double, const std::vector &, const rclcpp::Time &, - const std::vector & lidar_detected_entity) -> void override; + const std::vector & lidar_detected_entities) -> void override; }; } // namespace simple_sensor_simulator diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/occupancy_grid/occupancy_grid_sensor.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/occupancy_grid/occupancy_grid_sensor.hpp index 95af06dd0fc..a5f17dbd8aa 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/occupancy_grid/occupancy_grid_sensor.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/sensor_simulation/occupancy_grid/occupancy_grid_sensor.hpp @@ -126,7 +126,7 @@ class OccupancyGridSensor : public OccupancyGridSensorBase template <> auto OccupancyGridSensor::getOccupancyGrid( const std::vector & status, const rclcpp::Time & stamp, - const std::vector & lidar_detected_entity) -> nav_msgs::msg::OccupancyGrid; + const std::vector & lidar_detected_entities) -> nav_msgs::msg::OccupancyGrid; } // namespace simple_sensor_simulator #endif // SIMPLE_SENSOR_SIMULATOR__SENSOR_SIMULATION__OCCUPANCY_GRID__OCCUPANCY_GRID_SENSOR_HPP_ diff --git a/simulation/simple_sensor_simulator/src/sensor_simulation/occupancy_grid/occupancy_grid_sensor.cpp b/simulation/simple_sensor_simulator/src/sensor_simulation/occupancy_grid/occupancy_grid_sensor.cpp index 107e0b66d48..d947efe5d5d 100644 --- a/simulation/simple_sensor_simulator/src/sensor_simulation/occupancy_grid/occupancy_grid_sensor.cpp +++ b/simulation/simple_sensor_simulator/src/sensor_simulation/occupancy_grid/occupancy_grid_sensor.cpp @@ -41,14 +41,14 @@ geometry_msgs::Pose OccupancyGridSensorBase::getSensorPose( const std::vector OccupancyGridSensorBase::getDetectedObjects( const std::vector & status, - const std::vector & lidar_detected_entity) const + const std::vector & lidar_detected_entities) const { std::vector detected_entities; const auto pose = getSensorPose(status); for (const auto & s : status) { if (const auto has_detected = - std::find(lidar_detected_entity.begin(), lidar_detected_entity.end(), s.name()) != - lidar_detected_entity.end(); + std::find(lidar_detected_entities.begin(), lidar_detected_entities.end(), s.name()) != + lidar_detected_entities.end(); !has_detected) { continue; } @@ -66,7 +66,7 @@ const std::vector OccupancyGridSensorBase::getDetectedObjects( template <> auto OccupancyGridSensor::getOccupancyGrid( const std::vector & status, const rclcpp::Time & stamp, - const std::vector & lidar_detected_entity) -> nav_msgs::msg::OccupancyGrid + const std::vector & lidar_detected_entities) -> nav_msgs::msg::OccupancyGrid { // check if entities in `status` have unique names { @@ -105,10 +105,10 @@ auto OccupancyGridSensor::getOccupancyGrid( auto detected_entities = std::set(); { if (configuration_.filter_by_range()) { - auto v = getDetectedObjects(status, lidar_detected_entity); + auto v = getDetectedObjects(status, lidar_detected_entities); detected_entities.insert(v.begin(), v.end()); } else { - detected_entities.insert(lidar_detected_entity.begin(), lidar_detected_entity.end()); + detected_entities.insert(lidar_detected_entities.begin(), lidar_detected_entities.end()); } }