Skip to content

Commit

Permalink
feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy …
Browse files Browse the repository at this point in the history
…error (#9336)

* feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error

Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>

* add const to argument

Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>

---------

Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
  • Loading branch information
yhisaki authored Nov 18, 2024
1 parent a0c4ab4 commit 5dcb52b
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>message_filters</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ V at_or(const std::unordered_map<K, V> & map, const K & key, const V & value)
autoware_perception_msgs::msg::TrafficLightElement convert(
const tier4_perception_msgs::msg::TrafficLightElement & input)
{
typedef tier4_perception_msgs::msg::TrafficLightElement OldElem;
typedef autoware_perception_msgs::msg::TrafficLightElement NewElem;
using OldElem = tier4_perception_msgs::msg::TrafficLightElement;
using NewElem = autoware_perception_msgs::msg::TrafficLightElement;
static const std::unordered_map<OldElem::_color_type, NewElem::_color_type> color_map(
{{OldElem::RED, NewElem::RED},
{OldElem::AMBER, NewElem::AMBER},
Expand Down Expand Up @@ -292,7 +292,7 @@ void MultiCameraFusion::multiCameraFusion(std::map<IdType, FusionRecord> & fused
}

void MultiCameraFusion::groupFusion(
std::map<IdType, FusionRecord> & fused_record_map,
const std::map<IdType, FusionRecord> & fused_record_map,
std::map<IdType, FusionRecord> & grouped_record_map)
{
grouped_record_map.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,16 +65,16 @@ bool operator<(const FusionRecordArr & r1, const FusionRecordArr & r2)
class MultiCameraFusion : public rclcpp::Node
{
public:
typedef sensor_msgs::msg::CameraInfo CamInfoType;
typedef tier4_perception_msgs::msg::TrafficLightRoi RoiType;
typedef tier4_perception_msgs::msg::TrafficLight SignalType;
typedef tier4_perception_msgs::msg::TrafficLightArray SignalArrayType;
typedef tier4_perception_msgs::msg::TrafficLightRoiArray RoiArrayType;
typedef tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type IdType;
typedef autoware_perception_msgs::msg::TrafficLightGroup NewSignalType;
typedef autoware_perception_msgs::msg::TrafficLightGroupArray NewSignalArrayType;
using CamInfoType = sensor_msgs::msg::CameraInfo;
using RoiType = tier4_perception_msgs::msg::TrafficLightRoi;
using SignalType = tier4_perception_msgs::msg::TrafficLight;
using SignalArrayType = tier4_perception_msgs::msg::TrafficLightArray;
using RoiArrayType = tier4_perception_msgs::msg::TrafficLightRoiArray;
using IdType = tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type;
using NewSignalType = autoware_perception_msgs::msg::TrafficLightGroup;
using NewSignalArrayType = autoware_perception_msgs::msg::TrafficLightGroupArray;

typedef std::pair<RoiArrayType, SignalArrayType> RecordArrayType;
using RecordArrayType = std::pair<RoiArrayType, SignalArrayType>;

explicit MultiCameraFusion(const rclcpp::NodeOptions & node_options);

Expand All @@ -91,14 +91,14 @@ class MultiCameraFusion : public rclcpp::Node
const std::map<IdType, FusionRecord> & grouped_record_map, NewSignalArrayType & msg_out);

void groupFusion(
std::map<IdType, FusionRecord> & fused_record_map,
const std::map<IdType, FusionRecord> & fused_record_map,
std::map<IdType, FusionRecord> & grouped_record_map);

typedef mf::sync_policies::ExactTime<CamInfoType, RoiArrayType, SignalArrayType> ExactSyncPolicy;
typedef mf::Synchronizer<ExactSyncPolicy> ExactSync;
typedef mf::sync_policies::ApproximateTime<CamInfoType, RoiArrayType, SignalArrayType>
ApproximateSyncPolicy;
typedef mf::Synchronizer<ApproximateSyncPolicy> ApproximateSync;
using ExactSyncPolicy = mf::sync_policies::ExactTime<CamInfoType, RoiArrayType, SignalArrayType>;
using ExactSync = mf::Synchronizer<ExactSyncPolicy>;
using ApproximateSyncPolicy =
mf::sync_policies::ApproximateTime<CamInfoType, RoiArrayType, SignalArrayType>;
using ApproximateSync = mf::Synchronizer<ApproximateSyncPolicy>;

std::vector<std::unique_ptr<mf::Subscriber<SignalArrayType>>> signal_subs_;
std::vector<std::unique_ptr<mf::Subscriber<RoiArrayType>>> roi_subs_;
Expand Down

0 comments on commit 5dcb52b

Please sign in to comment.