Skip to content

Commit

Permalink
feat!: change from autoware_auto_msgs to autoware_msgs (#30)
Browse files Browse the repository at this point in the history
* feat!: replace autoware_auto_msgs with autoware_msgs

Signed-off-by: mitsudome-r <[email protected]>

* style(pre-commit): autofix

* feat: port remaining autoware_auto_msgs to autoware_msgs  (#32)

* feat: port remaining autoware_auto_msgs to autoware_msgs

Signed-off-by: Ryohsuke Mitsudome <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: Ryohsuke Mitsudome <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

* remove <depend>autoware_msgs</depend>

Signed-off-by: M. Fatih Cırıt <[email protected]>

* remove non-existent dep

Signed-off-by: M. Fatih Cırıt <[email protected]>

---------

Signed-off-by: mitsudome-r <[email protected]>
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
Signed-off-by: M. Fatih Cırıt <[email protected]>
Co-authored-by: mitsudome-r <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Ryohsuke Mitsudome <[email protected]>
Co-authored-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
5 people authored Jun 4, 2024
1 parent 4c4080a commit 35de874
Show file tree
Hide file tree
Showing 39 changed files with 145 additions and 163 deletions.
4 changes: 0 additions & 4 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,6 @@ repositories:
type: git
url: https://github.com/autowarefoundation/autoware_internal_msgs.git
version: main
core/external/autoware_auto_msgs:
type: git
url: https://github.com/tier4/autoware_auto_msgs.git
version: tier4/main
# universe
universe/autoware.universe:
type: git
Expand Down
22 changes: 11 additions & 11 deletions common/tier4_control_rviz_plugin/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,20 +6,20 @@ This package is to mimic external control for simulation.

### Input

| Name | Type | Description |
| --------------------------------- | ------------------------------------------------- | ----------------------- |
| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Current GATE mode |
| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | Current velocity status |
| `/api/autoware/get/engage` | `tier4_external_api_msgs::srv::Engage` | Getting Engage |
| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | The state of GEAR |
| Name | Type | Description |
| --------------------------------- | -------------------------------------------- | ----------------------- |
| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Current GATE mode |
| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | Current velocity status |
| `/api/autoware/get/engage` | `tier4_external_api_msgs::srv::Engage` | Getting Engage |
| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | The state of GEAR |

### Output

| Name | Type | Description |
| -------------------------------- | ---------------------------------------------------------- | ----------------------- |
| `/control/gate_mode_cmd` | `tier4_control_msgs::msg::GateMode` | GATE mode |
| `/external/selected/control_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | AckermannControlCommand |
| `/external/selected/gear_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | GEAR |
| Name | Type | Description |
| -------------------------------- | -------------------------------------------- | --------------- |
| `/control/gate_mode_cmd` | `tier4_control_msgs::msg::GateMode` | GATE mode |
| `/external/selected/control_cmd` | `autoware_control_msgs::msg::ControlCommand` | Control command |
| `/external/selected/gear_cmd` | `autoware_vehicle_msgs::msg::GearCommand` | GEAR |

## Usage

Expand Down
4 changes: 2 additions & 2 deletions common/tier4_control_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
<depend>libqt5-widgets</depend>
Expand Down
22 changes: 11 additions & 11 deletions common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,11 +102,11 @@ ManualController::ManualController(QWidget * parent) : rviz_common::Panel(parent
void ManualController::update()
{
if (!raw_node_) return;
AckermannControlCommand ackermann;
Control control_cmd;
{
ackermann.stamp = raw_node_->get_clock()->now();
ackermann.lateral.steering_tire_angle = steering_angle_;
ackermann.longitudinal.speed = cruise_velocity_;
control_cmd.stamp = raw_node_->get_clock()->now();
control_cmd.lateral.steering_tire_angle = steering_angle_;
control_cmd.longitudinal.velocity = cruise_velocity_;
/**
* @brief Calculate desired acceleration by simple BackSteppingControl
* V = 0.5*(v-v_des)^2 >= 0
Expand All @@ -118,21 +118,21 @@ void ManualController::update()
const double v_des = cruise_velocity_;
const double a = current_acceleration_;
const double a_des = k * (v - v_des) + a;
ackermann.longitudinal.acceleration = std::clamp(a_des, -1.0, 1.0);
control_cmd.longitudinal.acceleration = std::clamp(a_des, -1.0, 1.0);
}
GearCommand gear_cmd;
{
const double eps = 0.001;
if (ackermann.longitudinal.speed > eps && current_velocity_ > -eps) {
if (control_cmd.longitudinal.velocity > eps && current_velocity_ > -eps) {
gear_cmd.command = GearCommand::DRIVE;
} else if (ackermann.longitudinal.speed < -eps && current_velocity_ < eps) {
} else if (control_cmd.longitudinal.velocity < -eps && current_velocity_ < eps) {
gear_cmd.command = GearCommand::REVERSE;
ackermann.longitudinal.acceleration *= -1.0;
control_cmd.longitudinal.acceleration *= -1.0;
} else {
gear_cmd.command = GearCommand::PARK;
}
}
pub_control_command_->publish(ackermann);
pub_control_command_->publish(control_cmd);
pub_gear_cmd_->publish(gear_cmd);
}

Expand Down Expand Up @@ -170,8 +170,8 @@ void ManualController::onInitialize()

pub_gate_mode_ = raw_node_->create_publisher<GateMode>("/control/gate_mode_cmd", rclcpp::QoS(1));

pub_control_command_ = raw_node_->create_publisher<AckermannControlCommand>(
"/external/selected/control_cmd", rclcpp::QoS(1));
pub_control_command_ =
raw_node_->create_publisher<Control>("/external/selected/control_cmd", rclcpp::QoS(1));

pub_gear_cmd_ = raw_node_->create_publisher<GearCommand>("/external/selected/gear_cmd", 1);
}
Expand Down
22 changes: 11 additions & 11 deletions common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,29 +24,29 @@
#include <rclcpp/rclcpp.hpp>
#include <rviz_common/panel.hpp>

#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_vehicle_msgs/msg/engage.hpp>
#include <autoware_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_vehicle_msgs/msg/gear_report.hpp>
#include <tier4_control_msgs/msg/gate_mode.hpp>
#include <tier4_external_api_msgs/srv/engage.hpp>

#include <memory>

namespace rviz_plugins
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_vehicle_msgs::msg::GearCommand;
using autoware_auto_vehicle_msgs::msg::VelocityReport;
using autoware_control_msgs::msg::Control;
using autoware_vehicle_msgs::msg::GearCommand;
using autoware_vehicle_msgs::msg::VelocityReport;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::Twist;
using tier4_control_msgs::msg::GateMode;
using EngageSrv = tier4_external_api_msgs::srv::Engage;
using autoware_auto_vehicle_msgs::msg::Engage;
using autoware_auto_vehicle_msgs::msg::GearReport;
using autoware_vehicle_msgs::msg::Engage;
using autoware_vehicle_msgs::msg::GearReport;

class ManualController : public rviz_common::Panel
{
Expand Down Expand Up @@ -77,7 +77,7 @@ public Q_SLOTS: // NOLINT for Qt
rclcpp::Subscription<VelocityReport>::SharedPtr sub_velocity_;
rclcpp::Subscription<Engage>::SharedPtr sub_engage_;
rclcpp::Publisher<tier4_control_msgs::msg::GateMode>::SharedPtr pub_gate_mode_;
rclcpp::Publisher<AckermannControlCommand>::SharedPtr pub_control_command_;
rclcpp::Publisher<Control>::SharedPtr pub_control_command_;
rclcpp::Publisher<GearCommand>::SharedPtr pub_gear_cmd_;
rclcpp::Client<EngageSrv>::SharedPtr client_engage_;
rclcpp::Subscription<GearReport>::SharedPtr sub_gear_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.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>

Expand All @@ -36,15 +36,15 @@ class LateralErrorPublisher : public rclcpp::Node
double yaw_threshold_to_search_closest_;

/* States */
autoware_auto_planning_msgs::msg::Trajectory::SharedPtr
autoware_planning_msgs::msg::Trajectory::SharedPtr
current_trajectory_ptr_; //!< @brief reference trajectory
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr
current_vehicle_pose_ptr_; //!< @brief current EKF pose
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr
current_ground_truth_pose_ptr_; //!< @brief current GNSS pose

/* Publishers and Subscribers */
rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr
rclcpp::Subscription<autoware_planning_msgs::msg::Trajectory>::SharedPtr
sub_trajectory_; //!< @brief subscription for reference trajectory
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr
sub_vehicle_pose_; //!< @brief subscription for vehicle pose
Expand All @@ -60,7 +60,7 @@ class LateralErrorPublisher : public rclcpp::Node
/**
* @brief set current_trajectory_ with received message
*/
void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr);
void onTrajectory(const autoware_planning_msgs::msg::Trajectory::SharedPtr);
/**
* @brief set current_vehicle_pose_ with received message
*/
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,7 +10,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
Expand Down
4 changes: 2 additions & 2 deletions common/tier4_debug_tools/src/lateral_error_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op
declare_parameter("yaw_threshold_to_search_closest", M_PI / 4.0);

/* Publishers and Subscribers */
sub_trajectory_ = create_subscription<autoware_auto_planning_msgs::msg::Trajectory>(
sub_trajectory_ = create_subscription<autoware_planning_msgs::msg::Trajectory>(
"~/input/reference_trajectory", rclcpp::QoS{1},
std::bind(&LateralErrorPublisher::onTrajectory, this, _1));
sub_vehicle_pose_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
Expand All @@ -44,7 +44,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op
}

void LateralErrorPublisher::onTrajectory(
const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg)
const autoware_planning_msgs::msg::Trajectory::SharedPtr msg)
{
current_trajectory_ptr_ = msg;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class AnalyzerCore
odd_raw_data_ = getRawData(timestamp);
}

void setMap(const HADMapBin & msg) { route_handler_.setMap(msg); }
void setMap(const LaneletMapBin & msg) { route_handler_.setMap(msg); }

void clearData() { odd_raw_data_ = std::nullopt; }

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,12 @@ class DrivingEnvironmentAnalyzerNode : public rclcpp::Node
explicit DrivingEnvironmentAnalyzerNode(const rclcpp::NodeOptions & node_options);

private:
void onMap(const HADMapBin::ConstSharedPtr map_msg);
void onMap(const LaneletMapBin::ConstSharedPtr map_msg);
void analyze();

std::shared_ptr<analyzer_core::AnalyzerCore> analyzer_;

rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_map_;
rclcpp::TimerBase::SharedPtr timer_;
rosbag2_cpp::Reader reader_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ public Q_SLOTS:
void onClickAnalyzeDynamicODDFactor();

private:
void onMap(const HADMapBin::ConstSharedPtr map_msg);
void onMap(const LaneletMapBin::ConstSharedPtr map_msg);

std::shared_ptr<analyzer_core::AnalyzerCore> analyzer_;

Expand All @@ -75,7 +75,7 @@ public Q_SLOTS:
QPushButton * set_timestamp_btn_;

rclcpp::Node::SharedPtr raw_node_;
rclcpp::Subscription<HADMapBin>::SharedPtr sub_map_;
rclcpp::Subscription<LaneletMapBin>::SharedPtr sub_map_;
rclcpp::Publisher<Odometry>::SharedPtr pub_odometry_;
rclcpp::Publisher<PredictedObjects>::SharedPtr pub_objects_;
rclcpp::Publisher<TFMessage>::SharedPtr pub_tf_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@
#include "tier4_rtc_msgs/msg/command.hpp"
#include "tier4_rtc_msgs/msg/cooperate_status_array.hpp"
#include "tier4_rtc_msgs/msg/module.hpp"
#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
Expand All @@ -40,9 +40,9 @@ using nav_msgs::msg::Odometry;
using tf2_msgs::msg::TFMessage;

// autoware
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_map_msgs::msg::LaneletMapBin;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::LaneletRoute;
using tier4_rtc_msgs::msg::Command;
using tier4_rtc_msgs::msg::CooperateStatusArray;
Expand Down
5 changes: 2 additions & 3 deletions driving_environment_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,9 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>behavior_path_planner_common</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
Expand Down
2 changes: 1 addition & 1 deletion driving_environment_analyzer/src/analyzer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ void AnalyzerCore::setBagFile(const std::string & file_name)
route_handler_.setRoute(opt_route.value());
}

const auto opt_map = getLastTopic<HADMapBin>("/map/vector_map");
const auto opt_map = getLastTopic<LaneletMapBin>("/map/vector_map");
if (opt_map.has_value()) {
route_handler_.setMap(opt_map.value());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ DrivingEnvironmentAnalyzerNode::DrivingEnvironmentAnalyzerNode(
timer_ = rclcpp::create_timer(
this, get_clock(), 100ms, std::bind(&DrivingEnvironmentAnalyzerNode::analyze, this));

sub_map_ = create_subscription<HADMapBin>(
sub_map_ = create_subscription<LaneletMapBin>(
"input/lanelet2_map", rclcpp::QoS{1}.transient_local(),
std::bind(&DrivingEnvironmentAnalyzerNode::onMap, this, _1));

Expand All @@ -42,7 +42,7 @@ DrivingEnvironmentAnalyzerNode::DrivingEnvironmentAnalyzerNode(
analyzer_->setBagFile(declare_parameter<std::string>("bag_path"));
}

void DrivingEnvironmentAnalyzerNode::onMap(const HADMapBin::ConstSharedPtr msg)
void DrivingEnvironmentAnalyzerNode::onMap(const LaneletMapBin::ConstSharedPtr msg)
{
analyzer_->setMap(*msg);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ void DrivingEnvironmentAnalyzerPanel::onInitialize()

raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

sub_map_ = raw_node_->create_subscription<HADMapBin>(
sub_map_ = raw_node_->create_subscription<LaneletMapBin>(
"/map/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&DrivingEnvironmentAnalyzerPanel::onMap, this, _1));

Expand All @@ -126,7 +126,7 @@ void DrivingEnvironmentAnalyzerPanel::onInitialize()
analyzer_ = std::make_shared<analyzer_core::AnalyzerCore>(*raw_node_);
}

void DrivingEnvironmentAnalyzerPanel::onMap(const HADMapBin::ConstSharedPtr msg)
void DrivingEnvironmentAnalyzerPanel::onMap(const LaneletMapBin::ConstSharedPtr msg)
{
analyzer_->setMap(*msg);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include "autoware_auto_planning_msgs/msg/path.hpp"
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_planning_msgs/msg/path.hpp"
#include "autoware_planning_msgs/msg/trajectory.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "tier4_debug_msgs/msg/float64_multi_array_stamped.hpp"
#include "tier4_planning_msgs/msg/path_with_lane_id.hpp"

#include <iostream>
#include <map>
Expand All @@ -35,11 +35,11 @@

namespace planning_debug_tools
{
using autoware_auto_planning_msgs::msg::Path;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::Path;
using autoware_planning_msgs::msg::Trajectory;
using nav_msgs::msg::Odometry;
using planning_debug_tools::msg::TrajectoryDebugInfo;
using tier4_planning_msgs::msg::PathWithLaneId;

template <typename T>
class TrajectoryAnalyzer
Expand Down
Loading

0 comments on commit 35de874

Please sign in to comment.