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

fix(autonomous_emergency_braking): fix imu tranform to base_link #3812

Merged
merged 3 commits into from
May 25, 2023
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 @@ -23,6 +23,7 @@
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -60,6 +61,7 @@ using vehicle_info_util::VehicleInfo;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
using Path = std::vector<geometry_msgs::msg::Pose>;
using Vector3 = geometry_msgs::msg::Vector3;

struct ObjectData
{
Expand Down Expand Up @@ -155,7 +157,7 @@ class AEB : public rclcpp::Node

PointCloud2::SharedPtr obstacle_ros_pointcloud_ptr_{nullptr};
VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr};
Imu::ConstSharedPtr imu_ptr_{nullptr};
Vector3::SharedPtr angular_velocity_ptr_{nullptr};
Trajectory::ConstSharedPtr predicted_traj_ptr_{nullptr};
AutowareState::ConstSharedPtr autoware_state_{nullptr};

Expand Down
20 changes: 17 additions & 3 deletions control/autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,21 @@ void AEB::onVelocity(const VelocityReport::ConstSharedPtr input_msg)

void AEB::onImu(const Imu::ConstSharedPtr input_msg)
{
imu_ptr_ = input_msg;
// transform imu
geometry_msgs::msg::TransformStamped transform_stamped{};
try {
transform_stamped = tf_buffer_.lookupTransform(
"base_link", input_msg->header.frame_id, input_msg->header.stamp,
rclcpp::Duration::from_seconds(0.5));
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR_STREAM(
get_logger(),
"[AEB] Failed to look up transform from base_link to" << input_msg->header.frame_id);
return;
}

angular_velocity_ptr_ = std::make_shared<Vector3>();
tf2::doTransform(input_msg->angular_velocity, *angular_velocity_ptr_, transform_stamped);
}

void AEB::onPredictedTrajectory(
Expand Down Expand Up @@ -225,7 +239,7 @@ bool AEB::isDataReady()
return missing("object pointcloud");
}

if (use_imu_path_ && !imu_ptr_) {
if (use_imu_path_ && !angular_velocity_ptr_) {
return missing("imu");
}

Expand Down Expand Up @@ -286,7 +300,7 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
if (use_imu_path_) {
Path ego_path;
std::vector<Polygon2d> ego_polys;
const double current_w = imu_ptr_->angular_velocity.z;
const double current_w = angular_velocity_ptr_->z;
constexpr double color_r = 0.0 / 256.0;
constexpr double color_g = 148.0 / 256.0;
constexpr double color_b = 205.0 / 256.0;
Expand Down