Skip to content

Commit

Permalink
feature: add *.param.yaml to manage parameters (autowarefoundation#50)
Browse files Browse the repository at this point in the history
* make *.param.yaml in imgproc packages

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* make *.param.yaml in initializer packages

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* make *.param.yaml in map packages

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* make *.param.yaml in pf packages

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* make *.param.yaml in twist packages

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* fix expressway parameter

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* fix override_frame_id

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* remove default parameters

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

* fix some remaining invalida parameters

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>

---------

Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>
  • Loading branch information
KYabuuchi committed May 31, 2023
1 parent 13f68b6 commit 15f9ff5
Show file tree
Hide file tree
Showing 58 changed files with 360 additions and 259 deletions.
2 changes: 1 addition & 1 deletion localization/yabloc/imgproc/graph_segment/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,4 @@ target_include_directories(${TARGET} SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIRS})
target_link_libraries(${TARGET} ${OpenCV_LIBS})

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/**:
ros__parameters:
# graph_node selects a road surface area from around this height
target_height_ratio: 0.85

#
target_candidate_box_width: 15

# graph_segment_node will pickup additional roadlike areas
pickup_additional_graph_segment: true

# used when the pickup_additional_graph_segment: true
similarity_score_threshold: 0.8

# parameters for cv::ximgproc::segmentation
sigma: 0.5
k: 300.0
min_size: 100.0
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ namespace yabloc::graph_segment
{
GraphSegment::GraphSegment()
: Node("graph_segment"),
target_height_ratio_(declare_parameter<float>("target_height_ratio", 0.85)),
target_candidate_box_width_(declare_parameter<int>("target_candidate_box_width", 15))
target_height_ratio_(declare_parameter<float>("target_height_ratio")),
target_candidate_box_width_(declare_parameter<int>("target_candidate_box_width"))
{
using std::placeholders::_1;

Expand All @@ -37,15 +37,15 @@ GraphSegment::GraphSegment()
pub_mask_image_ = create_publisher<Image>("mask_image", 10);
pub_debug_image_ = create_publisher<Image>("segmented_image", 10);

const double sigma = declare_parameter<double>("sigma", 0.5);
const float k = declare_parameter<float>("k", 300);
const int min_size = declare_parameter<double>("min_size", 100);
const double sigma = declare_parameter<double>("sigma");
const float k = declare_parameter<float>("k");
const int min_size = declare_parameter<double>("min_size");
segmentation_ = cv::ximgproc::segmentation::createGraphSegmentation(sigma, k, min_size);

// additional area pickup module
if (declare_parameter<bool>("pickup_additional_areas", true)) {
similar_area_searcher_ = std::make_unique<SimilarAreaSearcher>(
declare_parameter<float>("similarity_score_threshold", 0.8));
similar_area_searcher_ =
std::make_unique<SimilarAreaSearcher>(declare_parameter<float>("similarity_score_threshold"));
}
}

Expand Down
2 changes: 1 addition & 1 deletion localization/yabloc/imgproc/segment_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,4 +36,4 @@ target_include_directories(${TARGET} PUBLIC include ${EIGEN3_INCLUDE_DIRS} ${PCL
target_link_libraries(${TARGET} ${PCL_LIBRARIES} ${OpenCV_LIBS})

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
min_segment_length: 1.5 # if it is negative, it is unlimited
max_segment_distance: 30.0 # if it is negative, it is unlimited
max_lateral_distance: 10.0 # if it is negative, it is unlimited
publish_image_with_segment_for_debug: true
max_range: 20.0
image_size: 800 # debug
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@ namespace yabloc::segment_filter
{
SegmentFilter::SegmentFilter()
: Node("segment_filter"),
image_size_(declare_parameter<int>("image_size", 800)),
max_range_(declare_parameter<float>("max_range", 20.f)),
min_segment_length_(declare_parameter<float>("min_segment_length", -1)),
max_segment_distance_(declare_parameter<float>("max_segment_distance", -1)),
max_lateral_distance_(declare_parameter<float>("max_lateral_distance", -1)),
image_size_(declare_parameter<int>("image_size")),
max_range_(declare_parameter<float>("max_range")),
min_segment_length_(declare_parameter<float>("min_segment_length")),
max_segment_distance_(declare_parameter<float>("max_segment_distance")),
max_lateral_distance_(declare_parameter<float>("max_lateral_distance")),
info_(this),
synchro_subscriber_(this, "line_segments_cloud", "mask_image"),
tf_subscriber_(this->get_clock())
Expand Down Expand Up @@ -92,14 +92,16 @@ void SegmentFilter::execute(const PointCloud2 & line_segments_msg, const Image &

const rclcpp::Time stamp = line_segments_msg.header.stamp;

pcl::PointCloud<pcl::PointNormal>::Ptr line_segments_cloud{new pcl::PointCloud<pcl::PointNormal>()};
pcl::PointCloud<pcl::PointNormal>::Ptr line_segments_cloud{
new pcl::PointCloud<pcl::PointNormal>()};
cv::Mat mask_image = common::decompress_to_cv_mat(segment_msg);
pcl::fromROSMsg(line_segments_msg, *line_segments_cloud);

const std::set<int> indices = filt_by_mask(mask_image, *line_segments_cloud);

pcl::PointCloud<pcl::PointNormal> valid_edges = project_lines(*line_segments_cloud, indices);
pcl::PointCloud<pcl::PointNormal> invalid_edges = project_lines(*line_segments_cloud, indices, true);
pcl::PointCloud<pcl::PointNormal> invalid_edges =
project_lines(*line_segments_cloud, indices, true);

// Projected line segments
{
Expand Down Expand Up @@ -141,12 +143,14 @@ void SegmentFilter::execute(const PointCloud2 & line_segments_msg, const Image &
{
pcl::PointCloud<pcl::PointXYZLNormal> combined_debug_edges;
for (size_t index = 0; index < line_segments_cloud->size(); ++index) {
const pcl::PointNormal& pn = line_segments_cloud->at(index);
const pcl::PointNormal & pn = line_segments_cloud->at(index);
pcl::PointXYZLNormal pln;
pln.getVector3fMap() = pn.getVector3fMap();
pln.getNormalVector3fMap() = pn.getNormalVector3fMap();
if (indices.count(index) > 0) pln.label = 255;
else pln.label = 0;
if (indices.count(index) > 0)
pln.label = 255;
else
pln.label = 0;
combined_debug_edges.push_back(pln);
}
common::publish_cloud(*pub_debug_cloud_, combined_debug_edges, stamp);
Expand Down
2 changes: 1 addition & 1 deletion localization/yabloc/imgproc/undistort/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,4 +27,4 @@ ament_auto_add_executable(${TARGET} src/undistort_node.cpp)
target_link_libraries(${TARGET} ${OpenCV_LIBS})

# ===================================================
ament_auto_package(INSTALL_TO_SHARE launch)
ament_auto_package(INSTALL_TO_SHARE launch config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
use_sensor_qos: true
width: 800
override_frame_id: "" # Value for overriding the camera's frame_id. If blank, frame_id of static_tf is not overwritten
6 changes: 3 additions & 3 deletions localization/yabloc/imgproc/undistort/src/undistort_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@ class UndistortNode : public rclcpp::Node

UndistortNode()
: Node("undistort"),
OUTPUT_WIDTH(declare_parameter("width", 800)),
OVERRIDE_FRAME_ID(declare_parameter("override_frame_id", ""))
OUTPUT_WIDTH(declare_parameter<int>("width")),
OVERRIDE_FRAME_ID(declare_parameter<std::string>("override_frame_id"))
{
using std::placeholders::_1;

rclcpp::QoS qos{10};
if (declare_parameter("use_sensor_qos", false)) {
if (declare_parameter<bool>("use_sensor_qos")) {
qos = rclcpp::QoS(10).durability_volatile().best_effort();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,4 +41,4 @@ target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL
target_link_libraries(${TARGET} ${PCL_LIBRARIES} Sophus::Sophus)

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
angle_resolution: 30
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
namespace yabloc
{
CameraPoseInitializer::CameraPoseInitializer()
: Node("camera_pose_initializer"), angle_resolution_{declare_parameter("angle_resolution", 30)}
: Node("camera_pose_initializer"), angle_resolution_{declare_parameter<int>("angle_resolution")}
{
using std::placeholders::_1;
using std::placeholders::_2;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,4 +29,4 @@ target_include_directories(${TARGET} PUBLIC include)
target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS})

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
cov_xx_yy: [2.0,0.25]
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class ParticleInitializer : public rclcpp::Node
ParticleInitializer();

private:
const Eigen::Vector2d cov_xx_yy_;
const std::vector<double> cov_xx_yy_;
rclcpp::Subscription<PoseCovStamped>::SharedPtr sub_initialpose_;
rclcpp::Publisher<PoseCovStamped>::SharedPtr pub_initialpose_;
rclcpp::Publisher<Marker>::SharedPtr pub_marker_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ namespace yabloc::modularized_particle_filter
{
ParticleInitializer::ParticleInitializer()
: Node("particle_initializer"),
cov_xx_yy_{declare_parameter("cov_xx_yy", std::vector<double>{4.0, 0.25}).data()}
cov_xx_yy_{this->template declare_parameter<std::vector<double>>("cov_xx_yy")}
{
using std::placeholders::_1;

Expand Down Expand Up @@ -101,7 +101,7 @@ ParticleInitializer::PoseCovStamped ParticleInitializer::rectify_initial_pose(
msg.pose.pose.orientation.z = std::sin(theta / 2);

Eigen::Matrix2f cov;
cov << cov_xx_yy_(0), 0, 0, cov_xx_yy_(1);
cov << cov_xx_yy_.at(0), 0, 0, cov_xx_yy_.at(1);
Eigen::Rotation2D r(theta);
cov = r * cov * r.inverse();

Expand Down
2 changes: 1 addition & 1 deletion localization/yabloc/map/ground_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,4 +44,4 @@ target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL
target_link_libraries(${TARGET} ${PCL_LIBRARIES} Sophus::Sophus glog::glog)

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
force_zero_tilt: false
K: 50
R: 10
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ namespace yabloc ::ground_server
{
GroundServer::GroundServer()
: Node("ground_server"),
force_zero_tilt_(declare_parameter("force_zero_tilt", false)),
R(declare_parameter("R", 20)),
K(declare_parameter("K", 50))
force_zero_tilt_(declare_parameter<bool>("force_zero_tilt")),
R(declare_parameter<int>("R")),
K(declare_parameter<int>("K"))
{
using std::placeholders::_1;
using std::placeholders::_2;
Expand Down
8 changes: 4 additions & 4 deletions localization/yabloc/map/ll2_decomposer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,13 +33,13 @@ target_include_directories(ll2_util PUBLIC include 3rd/regulatory_elements/inclu

# ===================================================
# Executable
set(TARGET ll2_decompose_node)
set(TARGET ll2_decomposer_node)
ament_auto_add_executable(${TARGET}
src/ll2_decompose_core.cpp
src/ll2_decompose_node.cpp)
src/ll2_decomposer_core.cpp
src/ll2_decomposer_node.cpp)
target_include_directories(${TARGET} PUBLIC include)
target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
target_link_libraries(${TARGET} ${PCL_LIBRARIES} ll2_util)

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
road_marking_labels: [cross_walk, zebra_marking, line_thin, line_thick, pedestrian_marking, stop_line, road_border]
sign_board_labels: [sign-board]
bounding_box_labels: [none]
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ Ll2Decomposer::Ll2Decomposer() : Node("ll2_to_image")

auto load_lanelet2_labels =
[this](const std::string & param_name, std::set<std::string> & labels) -> void {
declare_parameter(param_name, std::vector<std::string>{});
this->template declare_parameter<std::vector<std::string>>(param_name);
auto label_array = get_parameter(param_name).as_string_array();
for (auto l : label_array) labels.insert(l);
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,4 @@ target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL
target_link_libraries(${TARGET} Sophus::Sophus ${PCL_LIBRARIES} glog::glog)

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
# Declared in AbstParticleCorrector
acceptable_max_delay: 1.0
visualize: false

# Declared in ll2_cost_map
image_size: 800 # cost map image made by lanelet2
max_range: 40.0 # [m] a cost map scale size
gamma: 5.0 # cost map intensity gradient

min_prob: 0.1 # minimum weight of particles
far_weight_gain: 0.001 # exp(-far_weight_gain_ * squared_norm) is multiplied earch measurement
enabled_at_first: true # developing feature
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,14 @@ FastCosSin fast_math;

CameraParticleCorrector::CameraParticleCorrector()
: AbstCorrector("camera_particle_corrector"),
min_prob_(declare_parameter<float>("min_prob", 0.01)),
far_weight_gain_(declare_parameter<float>("far_weight_gain", 0.001)),
min_prob_(declare_parameter<float>("min_prob")),
far_weight_gain_(declare_parameter<float>("far_weight_gain")),
cost_map_(this)
{
using std::placeholders::_1;
using std::placeholders::_2;

enable_switch_ = declare_parameter<bool>("enabled_at_first", true);
enable_switch_ = declare_parameter<bool>("enabled_at_first");

// Publication
pub_image_ = create_publisher<Image>("match_image", 10);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,4 @@ target_include_directories(${TARGET} PUBLIC SYSTEM ${GeographicLib_INCLUDE_DIRS}
target_link_libraries(${TARGET} Sophus::Sophus)

# ===================================================
ament_auto_package()
ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/**:
ros__parameters:
# Declared in AbstParticleCorrector
acceptable_max_delay: 1.0
visualize: false

mahalanobis_distance_threshold: 30.0 # If the distance to GNSS observation exceeds this, the correction is skipped.
use_ublox_msg: true # Raw sensor data should not be used when running as Autoware.
ignore_less_than_float: false
#
for_fixed/max_weight: 5.0
for_fixed/flat_radius: 0.5
for_fixed/max_radius: 10.0
for_fixed/min_weight: 0.5
#
for_not_fixed/flat_radius: 5.0
for_not_fixed/max_radius: 20.0
for_not_fixed/min_weight: 0.5
for_not_fixed/max_weight: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -38,16 +38,16 @@ struct WeightManager

WeightManager(rclcpp::Node * node)
{
for_fixed_.flat_radius_ = node->declare_parameter("for_fixed/flat_radius", 0.5f);
for_fixed_.max_radius_ = node->declare_parameter("for_fixed/max_radius", 10.0f);
for_fixed_.min_weight_ = node->declare_parameter("for_fixed/min_weight", 0.5f);
for_fixed_.max_weight_ = node->declare_parameter("for_fixed/max_weight", 1.5f);
for_fixed_.flat_radius_ = node->declare_parameter<float>("for_fixed/flat_radius");
for_fixed_.max_radius_ = node->declare_parameter<float>("for_fixed/max_radius");
for_fixed_.min_weight_ = node->declare_parameter<float>("for_fixed/min_weight");
for_fixed_.max_weight_ = node->declare_parameter<float>("for_fixed/max_weight");
for_fixed_.compute_coeff();

for_not_fixed_.flat_radius_ = node->declare_parameter("for_not_fixed/flat_radius", 5.0f);
for_not_fixed_.max_radius_ = node->declare_parameter("for_not_fixed/max_radius", 20.0f);
for_not_fixed_.min_weight_ = node->declare_parameter("for_not_fixed/min_weight", 0.5f);
for_not_fixed_.max_weight_ = node->declare_parameter("for_not_fixed/max_weight", 1.0f);
for_not_fixed_.flat_radius_ = node->declare_parameter<float>("for_not_fixed/flat_radius");
for_not_fixed_.max_radius_ = node->declare_parameter<float>("for_not_fixed/max_radius");
for_not_fixed_.min_weight_ = node->declare_parameter<float>("for_not_fixed/min_weight");
for_not_fixed_.max_weight_ = node->declare_parameter<float>("for_not_fixed/max_weight");
for_not_fixed_.compute_coeff();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ namespace yabloc::modularized_particle_filter
{
GnssParticleCorrector::GnssParticleCorrector()
: AbstCorrector("gnss_particle_corrector"),
ignore_less_than_float_(declare_parameter<bool>("ignore_less_than_float", true)),
mahalanobis_distance_threshold_(declare_parameter<float>("mahalanobis_distance_threshold", 20.0)),
ignore_less_than_float_(declare_parameter<bool>("ignore_less_than_float")),
mahalanobis_distance_threshold_(declare_parameter<float>("mahalanobis_distance_threshold")),
weight_manager_(this)
{
using std::placeholders::_1;
Expand All @@ -33,7 +33,7 @@ GnssParticleCorrector::GnssParticleCorrector()
auto on_pose = std::bind(&GnssParticleCorrector::on_pose, this, _1);
auto on_ublox = std::bind(&GnssParticleCorrector::on_ublox, this, _1);
auto on_height = [this](const Float32 & height) { this->latest_height_ = height; };
if (declare_parameter<bool>("use_ublox_msg", true)) {
if (declare_parameter<bool>("use_ublox_msg")) {
ublox_sub_ = create_subscription<NavPVT>("input/navpvt", 10, on_ublox);
} else {
pose_sub_ = create_subscription<PoseCovStamped>("input/pose_with_covariance", 10, on_pose);
Expand Down
Loading

0 comments on commit 15f9ff5

Please sign in to comment.