Skip to content

Commit 950322e

Browse files
authored
More user-friendly log message for pointcloud_octomap_updater (#3514)
1 parent 716f734 commit 950322e

File tree

1 file changed

+30
-7
lines changed

1 file changed

+30
-7
lines changed

moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp

Lines changed: 30 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -74,15 +74,38 @@ PointCloudOctomapUpdater::PointCloudOctomapUpdater()
7474

7575
bool PointCloudOctomapUpdater::setParams(const std::string& name_space)
7676
{
77+
auto check_required = [this, &name_space](const std::string& key, auto& target,
78+
std::vector<std::string>& missing_keys) {
79+
if (!this->node_->get_parameter(name_space + "." + key, target))
80+
{
81+
missing_keys.push_back(key);
82+
}
83+
};
7784
// This parameter is optional
7885
node_->get_parameter_or(name_space + ".ns", ns_, std::string());
79-
return node_->get_parameter(name_space + ".point_cloud_topic", point_cloud_topic_) &&
80-
node_->get_parameter(name_space + ".max_range", max_range_) &&
81-
node_->get_parameter(name_space + ".padding_offset", padding_) &&
82-
node_->get_parameter(name_space + ".padding_scale", scale_) &&
83-
node_->get_parameter(name_space + ".point_subsample", point_subsample_) &&
84-
node_->get_parameter(name_space + ".max_update_rate", max_update_rate_) &&
85-
node_->get_parameter(name_space + ".filtered_cloud_topic", filtered_cloud_topic_);
86+
87+
std::vector<std::string> missing_keys;
88+
89+
check_required("point_cloud_topic", point_cloud_topic_, missing_keys);
90+
check_required("max_range", max_range_, missing_keys);
91+
check_required("padding_offset", padding_, missing_keys);
92+
check_required("padding_scale", scale_, missing_keys);
93+
check_required("point_subsample", point_subsample_, missing_keys);
94+
check_required("max_update_rate", max_update_rate_, missing_keys);
95+
check_required("filtered_cloud_topic", filtered_cloud_topic_, missing_keys);
96+
97+
if (missing_keys.empty())
98+
{
99+
return true;
100+
}
101+
std::ostringstream oss;
102+
for (const auto& name : missing_keys)
103+
{
104+
oss << ", "
105+
<< "'" << name << "'";
106+
}
107+
RCLCPP_ERROR(node_->get_logger(), "Missing parameters under '%s': %s", name_space.c_str(), oss.str().c_str());
108+
return false;
86109
}
87110

88111
bool PointCloudOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node)

0 commit comments

Comments
 (0)