Skip to content

Commit

Permalink
feat(surround_obstacle_checker): use polling subscriber
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Jun 5, 2024
1 parent 4daa6a9 commit 49403f3
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include "surround_obstacle_checker/debug_marker.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"

#include <motion_utils/vehicle/vehicle_state_checker.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -110,9 +111,12 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
rclcpp::TimerBase::SharedPtr timer_;

// publisher and subscriber
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_pointcloud_;
rclcpp::Subscription<PredictedObjects>::SharedPtr sub_dynamic_objects_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odometry_;
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry> sub_odometry_{
this, "~/input/odometry"};
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::PointCloud2>
sub_pointcloud_{this, "~/input/pointcloud"};
tier4_autoware_utils::InterProcessPollingSubscriber<PredictedObjects> sub_dynamic_objects_{
this, "~/input/objects"};
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr pub_stop_reason_;
rclcpp::Publisher<VelocityLimitClearCommand>::SharedPtr pub_clear_velocity_limit_;
rclcpp::Publisher<VelocityLimit>::SharedPtr pub_velocity_limit_;
Expand Down
31 changes: 4 additions & 27 deletions planning/surround_obstacle_checker/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,17 +206,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio
pub_velocity_limit_ = this->create_publisher<VelocityLimit>(
"~/output/max_velocity", rclcpp::QoS{1}.transient_local());

Check notice on line 208 in planning/surround_obstacle_checker/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Large Method

SurroundObstacleCheckerNode::SurroundObstacleCheckerNode is no longer above the threshold for lines of code
// Subscribers
sub_pointcloud_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS(),
std::bind(&SurroundObstacleCheckerNode::onPointCloud, this, std::placeholders::_1));
sub_dynamic_objects_ = this->create_subscription<PredictedObjects>(
"~/input/objects", 1,
std::bind(&SurroundObstacleCheckerNode::onDynamicObjects, this, std::placeholders::_1));
sub_odometry_ = this->create_subscription<nav_msgs::msg::Odometry>(
"~/input/odometry", 1,
std::bind(&SurroundObstacleCheckerNode::onOdometry, this, std::placeholders::_1));

// Parameter callback
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&SurroundObstacleCheckerNode::onParam, this, std::placeholders::_1));
Expand Down Expand Up @@ -282,6 +271,10 @@ rcl_interfaces::msg::SetParametersResult SurroundObstacleCheckerNode::onParam(

void SurroundObstacleCheckerNode::onTimer()
{
odometry_ptr_ = sub_odometry_.takeData();
pointcloud_ptr_ = sub_pointcloud_.takeData();
object_ptr_ = sub_dynamic_objects_.takeData();

Check warning on line 276 in planning/surround_obstacle_checker/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

planning/surround_obstacle_checker/src/node.cpp#L274-L276

Added lines #L274 - L276 were not covered by tests

Check notice on line 277 in planning/surround_obstacle_checker/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

SurroundObstacleCheckerNode::onTimer already has high cyclomatic complexity, and now it increases in Lines of Code from 73 to 76. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
if (!odometry_ptr_) {
RCLCPP_INFO_THROTTLE(
this->get_logger(), *this->get_clock(), 5000 /* ms */, "waiting for current velocity...");
Expand Down Expand Up @@ -377,22 +370,6 @@ void SurroundObstacleCheckerNode::onTimer()
debug_ptr_->publish();
}

void SurroundObstacleCheckerNode::onPointCloud(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
{
pointcloud_ptr_ = msg;
}

void SurroundObstacleCheckerNode::onDynamicObjects(const PredictedObjects::ConstSharedPtr msg)
{
object_ptr_ = msg;
}

void SurroundObstacleCheckerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
{
odometry_ptr_ = msg;
}

std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacle() const
{
const auto nearest_pointcloud = getNearestObstacleByPointCloud();
Expand Down

0 comments on commit 49403f3

Please sign in to comment.