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

Test/replace debug msgs #196

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
17 commits
Select commit Hold shift + click to select a range
5b951a7
feat(deviation_estimation_tools)!: replace tier4_debug_msgs with tier…
mitsudome-r Jan 22, 2025
21935b2
feat(tier4_debug_rviz_plugin)!: replace tier4_debug_msgs with tier4_i…
mitsudome-r Jan 22, 2025
aba16ba
feat(tier4_debug_tools)!: replace tier4_debug_msgs with tier4_interna…
mitsudome-r Jan 22, 2025
98bb6c1
feat(stop_accel_evaluator)!: replace tier4_debug_msgs with tier4_inte…
mitsudome-r Jan 22, 2025
8fd1201
feat(vehicle_cmd_analyzer)!: replace tier4_debug_msgs with tier4_inte…
mitsudome-r Jan 22, 2025
705be50
feat(autoware_planning_data_analyzer)!: replace tier4_debug_msgs with…
mitsudome-r Jan 22, 2025
b605f45
feat(planning_debug_tools)!: replace tier4_debug_msgs with tier4_inte…
mitsudome-r Jan 22, 2025
1acf2f5
feat(parameter_estimator)!: replace tier4_debug_msgs with tier4_inter…
mitsudome-r Jan 22, 2025
35e2778
Merge branch 'replace-debug-msgs-parameter-estiemator' into test/repl…
mitsudome-r Jan 22, 2025
56feb96
Merge branch 'replace-debug-msgs-planning-data-analyzer' into test/re…
mitsudome-r Jan 22, 2025
9137f86
Merge branch 'replace-debug-msgs-planning-debug-tools' into test/repl…
mitsudome-r Jan 22, 2025
584ba46
Merge branch 'replace-debug-msgs-stop-accel-evaluator' into test/repl…
mitsudome-r Jan 22, 2025
a8b32f4
Merge branch 'replace-debug-msgs-tier4-debug-rviz-plugin' into test/r…
mitsudome-r Jan 22, 2025
ba3aada
Merge branch 'replace-debug-msgs-tier4-debug-tools' into test/replace…
mitsudome-r Jan 22, 2025
02c9515
Merge branch 'replace-debug-msgs-vehicle-cmd-analyzer' into test/repl…
mitsudome-r Jan 22, 2025
04047f2
style(pre-commit): autofix
pre-commit-ci[bot] Jan 22, 2025
adeb9c0
fix: remove unnecessary dependency
mitsudome-r Jan 22, 2025
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
2 changes: 1 addition & 1 deletion common/tier4_debug_rviz_plugin/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,6 @@ Note that jsk_overlay_utils.cpp and jsk_overlay_utils.hpp are BSD license.

### Float32MultiArrayStampedPieChart

Pie chart from `tier4_debug_msgs::msg::Float32MultiArrayStamped`.
Pie chart from `autoware_internal_debug_msgs::msg::Float32MultiArrayStamped`.

![float32_multi_array_stamped_pie_chart](./images/float32_multi_array_stamped_pie_chart.png)
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@
#include <rviz_common/validate_floats.hpp>
#include <tier4_debug_rviz_plugin/jsk_overlay_utils.hpp>

#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp>

#include <mutex>

Expand All @@ -87,7 +87,7 @@ class Float32MultiArrayStampedPieChartDisplay : public rviz_common::Display
virtual void onDisable();
virtual void onInitialize();
virtual void processMessage(
const tier4_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg);
const autoware_internal_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg);
virtual void drawPlot(double val);
virtual void update(float wall_dt, float ros_dt);
// properties
Expand All @@ -114,7 +114,7 @@ class Float32MultiArrayStampedPieChartDisplay : public rviz_common::Display
rviz_common::properties::FloatProperty * med_color_threshold_property_;
rviz_common::properties::BoolProperty * clockwise_rotate_property_;

rclcpp::Subscription<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr sub_;
rclcpp::Subscription<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr sub_;
int left_;
int top_;
uint16_t texture_size_;
Expand Down
1 change: 0 additions & 1 deletion common/tier4_debug_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
<depend>rviz_common</depend>
<depend>rviz_default_plugins</depend>
<depend>rviz_rendering</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<class name="rviz_plugins/Float32MultiArrayStampedPieChart"
type="rviz_plugins::Float32MultiArrayStampedPieChartDisplay"
base_class_type="rviz_common::Display">
<description>Display drivable area of tier4_debug_msgs::msg::Float32MultiArrayStamped</description>
<description>Display drivable area of autoware_internal_debug_msgs::msg::Float32MultiArrayStamped</description>
</class>
<class name="rviz_plugins/StringStampedOverlayDisplay"
type="rviz_plugins::StringStampedOverlayDisplay"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,8 @@ Float32MultiArrayStampedPieChartDisplay::Float32MultiArrayStampedPieChartDisplay
: rviz_common::Display(), update_required_(false), first_time_(true), data_(0.0)
{
update_topic_property_ = new rviz_common::properties::StringProperty(
"Topic", "", "tier4_debug_msgs::msg::Float32MultiArrayStamped topic to subscribe to.", this,
"Topic", "",
"autoware_internal_debug_msgs::msg::Float32MultiArrayStamped topic to subscribe to.", this,
SLOT(updateTopic()), this);
data_index_property_ = new rviz_common::properties::IntProperty(
"data index", 0, "data index in message to visualize", this, SLOT(updateDataIndex()));
Expand Down Expand Up @@ -178,7 +179,7 @@ void Float32MultiArrayStampedPieChartDisplay::update(
}

void Float32MultiArrayStampedPieChartDisplay::processMessage(
const tier4_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg)
const autoware_internal_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg)
{
std::lock_guard<std::mutex> lock(mutex_);

Expand Down Expand Up @@ -297,10 +298,11 @@ void Float32MultiArrayStampedPieChartDisplay::subscribe()

if (topic_name.length() > 0 && topic_name != "/") {
rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node();
sub_ = raw_node->create_subscription<tier4_debug_msgs::msg::Float32MultiArrayStamped>(
topic_name, 1,
std::bind(
&Float32MultiArrayStampedPieChartDisplay::processMessage, this, std::placeholders::_1));
sub_ =
raw_node->create_subscription<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>(
topic_name, 1,
std::bind(
&Float32MultiArrayStampedPieChartDisplay::processMessage, this, std::placeholders::_1));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float32_stamped.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>

class LateralErrorPublisher : public rclcpp::Node
{
Expand All @@ -50,11 +50,11 @@ class LateralErrorPublisher : public rclcpp::Node
sub_vehicle_pose_; //!< @brief subscription for vehicle pose
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
sub_ground_truth_pose_; //!< @brief subscription for gnss pose
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
pub_control_lateral_error_; //!< @brief publisher for control lateral error
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
pub_localization_lateral_error_; //!< @brief publisher for localization lateral error
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32Stamped>::SharedPtr
pub_lateral_error_; //!< @brief publisher for lateral error (control + localization)

/**
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,14 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>

<exec_depend>launch_ros</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-rtree</exec_depend>
Expand Down
15 changes: 8 additions & 7 deletions common/tier4_debug_tools/src/lateral_error_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,13 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op
sub_ground_truth_pose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"~/input/ground_truth_pose_with_covariance", rclcpp::QoS{1},
std::bind(&LateralErrorPublisher::onGroundTruthPose, this, _1));
pub_control_lateral_error_ =
create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/control_lateral_error", 1);
pub_control_lateral_error_ = create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"~/control_lateral_error", 1);
pub_localization_lateral_error_ =
create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/localization_lateral_error", 1);
create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>(
"~/localization_lateral_error", 1);
pub_lateral_error_ =
create_publisher<tier4_debug_msgs::msg::Float32Stamped>("~/lateral_error", 1);
create_publisher<autoware_internal_debug_msgs::msg::Float32Stamped>("~/lateral_error", 1);
}

void LateralErrorPublisher::onTrajectory(
Expand Down Expand Up @@ -131,17 +132,17 @@ void LateralErrorPublisher::onGroundTruthPose(
RCLCPP_DEBUG(this->get_logger(), "localization_error: %f", lateral_error);

// Publish lateral errors
tier4_debug_msgs::msg::Float32Stamped control_msg;
autoware_internal_debug_msgs::msg::Float32Stamped control_msg;
control_msg.stamp = this->now();
control_msg.data = static_cast<float>(control_lateral_error);
pub_control_lateral_error_->publish(control_msg);

tier4_debug_msgs::msg::Float32Stamped localization_msg;
autoware_internal_debug_msgs::msg::Float32Stamped localization_msg;
localization_msg.stamp = this->now();
localization_msg.data = static_cast<float>(localization_lateral_error);
pub_localization_lateral_error_->publish(localization_msg);

tier4_debug_msgs::msg::Float32Stamped sum_msg;
autoware_internal_debug_msgs::msg::Float32Stamped sum_msg;
sum_msg.stamp = this->now();
sum_msg.data = static_cast<float>(lateral_error);
pub_lateral_error_->publish(sum_msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,23 +19,23 @@
#include "autoware/universe_utils/ros/self_pose_listener.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
#include "tier4_debug_msgs/msg/float32_stamped.hpp"

#include <deque>
#include <memory>

namespace stop_accel_evaluator
{
using autoware::universe_utils::SelfPoseListener;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32Stamped;
using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Float32Stamped;

class StopAccelEvaluatorNode : public rclcpp::Node
{
Expand Down
2 changes: 1 addition & 1 deletion control/stop_accel_evaluator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_signal_processing</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
Expand All @@ -18,7 +19,6 @@
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <rclcpp/rclcpp.hpp>

#include "autoware_control_msgs/msg/control.hpp"
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp"

#include <algorithm>
#include <memory>
Expand All @@ -33,7 +33,8 @@ class VehicleCmdAnalyzer : public rclcpp::Node
{
private:
rclcpp::Subscription<autoware_control_msgs::msg::Control>::SharedPtr sub_vehicle_cmd_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr pub_debug_;
rclcpp::Publisher<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>::SharedPtr
pub_debug_;
rclcpp::TimerBase::SharedPtr timer_control_;

std::shared_ptr<autoware_control_msgs::msg::Control> vehicle_cmd_ptr_{nullptr};
Expand Down
2 changes: 1 addition & 1 deletion control/vehicle_cmd_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
<build_depend>autoware_cmake</build_depend>

<depend>autoware_control_msgs</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions control/vehicle_cmd_analyzer/src/vehicle_cmd_analyzer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ VehicleCmdAnalyzer::VehicleCmdAnalyzer(const rclcpp::NodeOptions & options)
sub_vehicle_cmd_ = this->create_subscription<autoware_control_msgs::msg::Control>(
"/control/command/control_cmd", rclcpp::QoS(10),
std::bind(&VehicleCmdAnalyzer::callbackVehicleCommand, this, std::placeholders::_1));
pub_debug_ = create_publisher<tier4_debug_msgs::msg::Float32MultiArrayStamped>(
pub_debug_ = create_publisher<autoware_internal_debug_msgs::msg::Float32MultiArrayStamped>(
"~/debug_values", rclcpp::QoS{1});

// Timer
Expand Down Expand Up @@ -83,7 +83,7 @@ void VehicleCmdAnalyzer::publishDebugData()
debug_values_.setValues(DebugValues::TYPE::CURRENT_TARGET_LATERAL_ACC, a_lat);

// publish debug values
tier4_debug_msgs::msg::Float32MultiArrayStamped debug_msg{};
autoware_internal_debug_msgs::msg::Float32MultiArrayStamped debug_msg{};
debug_msg.stamp = this->now();
for (const auto & v : debug_values_.getValues()) {
debug_msg.data.push_back(v);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,13 @@
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist_with_covariance_stamped.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "std_msgs/msg/float64.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"

#include <iostream>
#include <memory>
Expand Down Expand Up @@ -71,7 +71,7 @@ class DeviationEstimator : public rclcpp::Node

std::string imu_link_frame_;

std::vector<tier4_debug_msgs::msg::Float64Stamped> vx_all_;
std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> vx_all_;
std::vector<geometry_msgs::msg::Vector3Stamped> gyro_all_;
std::vector<geometry_msgs::msg::PoseStamped> pose_buf_;
std::vector<TrajectoryData> traj_data_list_for_gyro_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
#include "deviation_estimator/autoware_universe_utils.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"

#include <tf2/transform_datatypes.h>

Expand All @@ -39,7 +39,7 @@
struct TrajectoryData
{
std::vector<geometry_msgs::msg::PoseStamped> pose_list;
std::vector<tier4_debug_msgs::msg::Float64Stamped> vx_list;
std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> vx_list;
std::vector<geometry_msgs::msg::Vector3Stamped> gyro_list;
};

Expand Down Expand Up @@ -95,12 +95,14 @@ double calculate_std_mean_const(const std::vector<T> & v, const double mean)

struct CompareMsgTimestamp
{
bool operator()(tier4_debug_msgs::msg::Float64Stamped const & t1, double const & t2) const
bool operator()(
autoware_internal_debug_msgs::msg::Float64Stamped const & t1, double const & t2) const
{
return rclcpp::Time(t1.stamp).seconds() < t2;
}

bool operator()(tier4_debug_msgs::msg::Float64Stamped const & t1, rclcpp::Time const & t2) const
bool operator()(
autoware_internal_debug_msgs::msg::Float64Stamped const & t1, rclcpp::Time const & t2) const
{
return rclcpp::Time(t1.stamp).seconds() < t2.seconds();
}
Expand Down Expand Up @@ -163,7 +165,7 @@ double norm_xy(const T p1, const U p2)
double clip_radian(const double rad);

geometry_msgs::msg::Point integrate_position(
const std::vector<tier4_debug_msgs::msg::Float64Stamped> & vx_list,
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list,
const std::vector<geometry_msgs::msg::Vector3Stamped> & gyro_list, const double coef_vx,
const double yaw_init);

Expand All @@ -176,9 +178,11 @@ geometry_msgs::msg::Vector3 integrate_orientation(
const std::vector<geometry_msgs::msg::Vector3Stamped> & gyro_list,
const geometry_msgs::msg::Vector3 & gyro_bias);

double get_mean_abs_vx(const std::vector<tier4_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_abs_vx(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_abs_wz(const std::vector<geometry_msgs::msg::Vector3Stamped> & gyro_list);
double get_mean_accel(const std::vector<tier4_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_accel(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);

geometry_msgs::msg::Vector3 transform_vector3(
const geometry_msgs::msg::Vector3 & vec, const geometry_msgs::msg::TransformStamped & transform);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "deviation_estimator/utils.hpp"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/vector3_stamped.hpp"
#include "tier4_debug_msgs/msg/float64_stamped.hpp"

#include <utility>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<build_depend>autoware_cmake</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
Expand All @@ -28,7 +29,6 @@
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<exec_depend>rosbag2_storage_mcap</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ void DeviationEstimator::callback_pose_with_covariance(
void DeviationEstimator::callback_wheel_odometry(
const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr wheel_odometry_msg_ptr)
{
tier4_debug_msgs::msg::Float64Stamped vx;
autoware_internal_debug_msgs::msg::Float64Stamped vx;
vx.stamp = wheel_odometry_msg_ptr->header.stamp;
vx.data = wheel_odometry_msg_ptr->longitudinal_velocity;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ int main(int argc, char ** argv)
if (index >= static_cast<int64_t>(trajectory_data_list.size())) {
trajectory_data_list.resize(index + 1);
}
tier4_debug_msgs::msg::Float64Stamped vx;
autoware_internal_debug_msgs::msg::Float64Stamped vx;
vx.stamp = velocity_status_msg->header.stamp;
vx.data = velocity_status_msg->longitudinal_velocity;
trajectory_data_list[index].vx_list.push_back(vx);
Expand Down
Loading
Loading