Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(velocity_smoother): introduce diagnostics #9933

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "autoware/osqp_interface/osqp_interface.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/math/unit_conversion.hpp"
#include "autoware/universe_utils/ros/diagnostics_interface.hpp"
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
#include "autoware/universe_utils/ros/polling_subscriber.hpp"
#include "autoware/universe_utils/ros/self_pose_listener.hpp"
Expand All @@ -45,8 +46,7 @@
#include "autoware_planning_msgs/msg/trajectory_point.hpp"
#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary
#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary
#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary
#include "visualization_msgs/msg/marker_array.hpp"

#include <iostream>
Expand All @@ -61,15 +61,15 @@ namespace autoware::velocity_smoother
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using TrajectoryPoints = std::vector<TrajectoryPoint>;
using autoware::universe_utils::DiagnosticsInterface;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_internal_debug_msgs::msg::Float32Stamped;
using autoware_internal_debug_msgs::msg::Float64Stamped;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
using nav_msgs::msg::Odometry;
using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary
using tier4_planning_msgs::msg::VelocityLimit; // temporary
using tier4_planning_msgs::msg::VelocityLimit; // temporary
using visualization_msgs::msg::MarkerArray;

struct Motion
Expand All @@ -89,7 +89,6 @@ class VelocitySmootherNode : public rclcpp::Node
private:
rclcpp::Publisher<Trajectory>::SharedPtr pub_trajectory_;
rclcpp::Publisher<MarkerArray>::SharedPtr pub_virtual_wall_;
rclcpp::Publisher<StopSpeedExceeded>::SharedPtr pub_over_stop_velocity_;
rclcpp::Subscription<Trajectory>::SharedPtr sub_current_trajectory_;
autoware::universe_utils::InterProcessPollingSubscriber<Odometry> sub_current_odometry_{
this, "/localization/kinematic_state"};
Expand Down Expand Up @@ -290,6 +289,8 @@ class VelocitySmootherNode : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;

mutable std::shared_ptr<autoware::universe_utils::TimeKeeper> time_keeper_{nullptr};

std::unique_ptr<DiagnosticsInterface> diagnostics_interface_{nullptr};
};
} // namespace autoware::velocity_smoother

Expand Down
17 changes: 9 additions & 8 deletions planning/autoware_velocity_smoother/src/node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/autoware_velocity_smoother/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.42 to 4.53, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -36,7 +36,8 @@
namespace autoware::velocity_smoother
{
VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_options)
: Node("velocity_smoother", node_options)
: Node("velocity_smoother", node_options),
diagnostics_interface_(std::make_unique<DiagnosticsInterface>(this, "velocity_smoother"))
{
using std::placeholders::_1;

Expand All @@ -63,7 +64,6 @@
pub_velocity_limit_ = create_publisher<VelocityLimit>(
"~/output/current_velocity_limit_mps", rclcpp::QoS{1}.transient_local());
pub_dist_to_stopline_ = create_publisher<Float32Stamped>("~/distance_to_stopline", 1);
pub_over_stop_velocity_ = create_publisher<StopSpeedExceeded>("~/stop_speed_exceeded", 1);
sub_current_trajectory_ = create_subscription<Trajectory>(
"~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1));

Expand Down Expand Up @@ -444,6 +444,7 @@
RCLCPP_DEBUG(get_logger(), "========================= run start =========================");
stop_watch_.tic();

diagnostics_interface_->clear();
base_traj_raw_ptr_ = msg;

// receive data
Expand Down Expand Up @@ -524,6 +525,10 @@

// Publish Calculation Time
publishStopWatchTime();

// Publish diagnostics
diagnostics_interface_->publish(now());

RCLCPP_DEBUG(get_logger(), "========================== run() end ==========================\n\n");
}

Expand Down Expand Up @@ -906,12 +911,8 @@
input_stop_vel, output_stop_vel, over_stop_velocity_warn_thr_);
}

{
StopSpeedExceeded msg{};
msg.stamp = this->now();
msg.stop_speed_exceeded = is_stop_velocity_exceeded;
pub_over_stop_velocity_->publish(msg);
}
diagnostics_interface_->add_key_value(
"The velocity on the stop point is larger than 0.", is_stop_velocity_exceeded);
}

void VelocitySmootherNode::applyExternalVelocityLimit(TrajectoryPoints & traj) const
Expand Down
Loading