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): use autoware internal Stamped messages #9749

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 @@ -39,12 +39,12 @@
#include <autoware/universe_utils/ros/published_time_publisher.hpp>

#include "autoware_adapi_v1_msgs/msg/operation_mode_state.hpp"
#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#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_debug_msgs/msg/float32_stamped.hpp" // temporary
#include "tier4_debug_msgs/msg/float64_stamped.hpp" // temporary
#include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" // temporary
#include "tier4_planning_msgs/msg/velocity_limit.hpp" // temporary
#include "visualization_msgs/msg/marker_array.hpp"
Expand All @@ -62,12 +62,12 @@ using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using TrajectoryPoints = std::vector<TrajectoryPoint>;
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_debug_msgs::msg::Float32Stamped; // temporary
using tier4_debug_msgs::msg::Float64Stamped; // temporary
using tier4_planning_msgs::msg::StopSpeedExceeded; // temporary
using tier4_planning_msgs::msg::VelocityLimit; // temporary
using visualization_msgs::msg::MarkerArray;
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_velocity_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_osqp_interface</depend>
Expand All @@ -34,7 +35,6 @@
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_planning_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Loading