Skip to content

Commit

Permalink
Merge branch 'main' into refactor/pointcloud_preprocessor-namespace-p…
Browse files Browse the repository at this point in the history
…refix
  • Loading branch information
amadeuszsz committed Jul 22, 2024
2 parents 01b39e7 + 86b39a2 commit 3e0099a
Show file tree
Hide file tree
Showing 4 changed files with 31 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ def create_parameter_dict(*args):
composable_node_descriptions=[
ComposableNode(
package="traffic_light_fine_detector",
plugin="traffic_light::TrafficLightFineDetectorNodelet",
plugin="autoware::traffic_light::TrafficLightFineDetectorNode",
name="traffic_light_fine_detector",
namespace="detection",
parameters=[fine_detector_model_param],
Expand Down
12 changes: 6 additions & 6 deletions perception/traffic_light_fine_detector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -75,15 +75,15 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
${CUDA_INCLUDE_DIRS}
)

ament_auto_add_library(traffic_light_fine_detector_nodelet SHARED
src/nodelet.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/traffic_light_fine_detector_node.cpp
)

target_include_directories(traffic_light_fine_detector_nodelet PUBLIC
target_include_directories(${PROJECT_NAME} PUBLIC
lib/include
)

target_link_libraries(traffic_light_fine_detector_nodelet
target_link_libraries(${PROJECT_NAME}
${NVINFER}
${NVONNXPARSER}
${NVINFER_PLUGIN}
Expand All @@ -94,8 +94,8 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
stdc++fs
)

rclcpp_components_register_node(traffic_light_fine_detector_nodelet
PLUGIN "traffic_light::TrafficLightFineDetectorNodelet"
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::traffic_light::TrafficLightFineDetectorNode"
EXECUTABLE traffic_light_fine_detector_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "traffic_light_fine_detector/nodelet.hpp"
#include "traffic_light_fine_detector_node.hpp"

#if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__)))
#include <filesystem>
Expand All @@ -22,6 +22,7 @@ namespace fs = ::std::filesystem;
namespace fs = ::std::experimental::filesystem;
#endif

#include <algorithm>
#include <memory>
#include <string>
#include <utility>
Expand All @@ -46,15 +47,14 @@ float calWeightedIou(

} // namespace

namespace traffic_light
namespace autoware::traffic_light
{
inline std::vector<float> toFloatVector(const std::vector<double> double_vector)
{
return std::vector<float>(double_vector.begin(), double_vector.end());
}

TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet(
const rclcpp::NodeOptions & options)
TrafficLightFineDetectorNode::TrafficLightFineDetectorNode(const rclcpp::NodeOptions & options)
: Node("traffic_light_fine_detector_node", options)
{
int num_class = 2;
Expand Down Expand Up @@ -95,7 +95,7 @@ TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet(

using std::chrono_literals::operator""ms;
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, std::bind(&TrafficLightFineDetectorNodelet::connectCb, this));
this, get_clock(), 100ms, std::bind(&TrafficLightFineDetectorNode::connectCb, this));

std::lock_guard<std::mutex> lock(connect_mutex_);
output_roi_pub_ = this->create_publisher<TrafficLightRoiArray>("~/output/rois", 1);
Expand All @@ -105,11 +105,10 @@ TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet(
approximate_sync_.reset(
new ApproximateSync(ApproximateSyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_));
approximate_sync_->registerCallback(
std::bind(&TrafficLightFineDetectorNodelet::callback, this, _1, _2, _3));
std::bind(&TrafficLightFineDetectorNode::callback, this, _1, _2, _3));
} else {
sync_.reset(new Sync(SyncPolicy(10), image_sub_, rough_roi_sub_, expect_roi_sub_));
sync_->registerCallback(
std::bind(&TrafficLightFineDetectorNodelet::callback, this, _1, _2, _3));
sync_->registerCallback(std::bind(&TrafficLightFineDetectorNode::callback, this, _1, _2, _3));
}

if (declare_parameter("build_only", false)) {
Expand All @@ -118,7 +117,7 @@ TrafficLightFineDetectorNodelet::TrafficLightFineDetectorNodelet(
}
}

void TrafficLightFineDetectorNodelet::connectCb()
void TrafficLightFineDetectorNode::connectCb()
{
std::lock_guard<std::mutex> lock(connect_mutex_);
if (output_roi_pub_->get_subscription_count() == 0) {
Expand All @@ -132,7 +131,7 @@ void TrafficLightFineDetectorNodelet::connectCb()
}
}

void TrafficLightFineDetectorNodelet::callback(
void TrafficLightFineDetectorNode::callback(
const sensor_msgs::msg::Image::ConstSharedPtr in_image_msg,
const TrafficLightRoiArray::ConstSharedPtr rough_roi_msg,
const TrafficLightRoiArray::ConstSharedPtr expect_roi_msg)
Expand Down Expand Up @@ -213,7 +212,7 @@ void TrafficLightFineDetectorNodelet::callback(
exe_time_pub_->publish(exe_time_msg);
}

float TrafficLightFineDetectorNodelet::evalMatchScore(
float TrafficLightFineDetectorNode::evalMatchScore(
std::map<int, TrafficLightRoi> & id2expectRoi,
std::map<int, tensorrt_yolox::ObjectArray> & id2detections,
std::map<int, tensorrt_yolox::Object> & id2bestDetection)
Expand All @@ -236,7 +235,7 @@ float TrafficLightFineDetectorNodelet::evalMatchScore(
return score_sum;
}

void TrafficLightFineDetectorNodelet::detectionMatch(
void TrafficLightFineDetectorNode::detectionMatch(
std::map<int, TrafficLightRoi> & id2expectRoi,
std::map<int, tensorrt_yolox::ObjectArray> & id2detections, TrafficLightRoiArray & out_rois)
{
Expand Down Expand Up @@ -298,7 +297,7 @@ void TrafficLightFineDetectorNodelet::detectionMatch(
}
}

bool TrafficLightFineDetectorNodelet::rosMsg2CvMat(
bool TrafficLightFineDetectorNode::rosMsg2CvMat(
const sensor_msgs::msg::Image::ConstSharedPtr image_msg, cv::Mat & image, std::string encode)
{
try {
Expand All @@ -313,8 +312,7 @@ bool TrafficLightFineDetectorNodelet::rosMsg2CvMat(
return true;
}

bool TrafficLightFineDetectorNodelet::fitInFrame(
cv::Point & lt, cv::Point & rb, const cv::Size & size)
bool TrafficLightFineDetectorNode::fitInFrame(cv::Point & lt, cv::Point & rb, const cv::Size & size)
{
const int width = static_cast<int>(size.width);
const int height = static_cast<int>(size.height);
Expand All @@ -334,7 +332,7 @@ bool TrafficLightFineDetectorNodelet::fitInFrame(
return true;
}

bool TrafficLightFineDetectorNodelet::readLabelFile(
bool TrafficLightFineDetectorNode::readLabelFile(
const std::string & filepath, std::vector<int> & tlr_label_id_, int & num_class)
{
std::ifstream labelsFile(filepath);
Expand All @@ -354,7 +352,7 @@ bool TrafficLightFineDetectorNodelet::readLabelFile(
return tlr_label_id_.size() != 0;
}

} // namespace traffic_light
} // namespace autoware::traffic_light

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(traffic_light::TrafficLightFineDetectorNodelet)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::traffic_light::TrafficLightFineDetectorNode)
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_
#define TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_
#ifndef TRAFFIC_LIGHT_FINE_DETECTOR_NODE_HPP_
#define TRAFFIC_LIGHT_FINE_DETECTOR_NODE_HPP_

#include <image_transport/image_transport.hpp>
#include <image_transport/subscriber_filter.hpp>
Expand Down Expand Up @@ -50,15 +50,15 @@ typedef struct Detection
float x, y, w, h, prob;
} Detection;

namespace traffic_light
namespace autoware::traffic_light
{
class TrafficLightFineDetectorNodelet : public rclcpp::Node
class TrafficLightFineDetectorNode : public rclcpp::Node
{
using TrafficLightRoi = tier4_perception_msgs::msg::TrafficLightRoi;
using TrafficLightRoiArray = tier4_perception_msgs::msg::TrafficLightRoiArray;

public:
explicit TrafficLightFineDetectorNodelet(const rclcpp::NodeOptions & options);
explicit TrafficLightFineDetectorNode(const rclcpp::NodeOptions & options);
void connectCb();
/**
* @brief main process function.
Expand Down Expand Up @@ -168,8 +168,8 @@ class TrafficLightFineDetectorNodelet : public rclcpp::Node

int batch_size_;
std::unique_ptr<tensorrt_yolox::TrtYoloX> trt_yolox_;
}; // TrafficLightFineDetectorNodelet
}; // TrafficLightFineDetectorNode

} // namespace traffic_light
} // namespace autoware::traffic_light

#endif // TRAFFIC_LIGHT_FINE_DETECTOR__NODELET_HPP_
#endif // TRAFFIC_LIGHT_FINE_DETECTOR_NODE_HPP_

0 comments on commit 3e0099a

Please sign in to comment.