Skip to content

Commit

Permalink
feat(simple_planning_sim): publish lateral acceleration (#5307)
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe authored Oct 13, 2023
1 parent c03b5ac commit def9ffc
Showing 1 changed file with 2 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -638,6 +638,7 @@ void SimplePlanningSimulator::publish_acceleration()
msg.header.frame_id = "/base_link";
msg.header.stamp = get_clock()->now();
msg.accel.accel.linear.x = vehicle_model_ptr_->getAx();
msg.accel.accel.linear.y = vehicle_model_ptr_->getWz() * vehicle_model_ptr_->getVx();

using COV_IDX = tier4_autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
constexpr auto COV = 0.001;
Expand All @@ -658,6 +659,7 @@ void SimplePlanningSimulator::publish_imu()
imu.header.frame_id = "base_link";
imu.header.stamp = now();
imu.linear_acceleration.x = vehicle_model_ptr_->getAx();
imu.linear_acceleration.y = vehicle_model_ptr_->getWz() * vehicle_model_ptr_->getVx();
constexpr auto COV = 0.001;
imu.linear_acceleration_covariance.at(COV_IDX::X_X) = COV;
imu.linear_acceleration_covariance.at(COV_IDX::Y_Y) = COV;
Expand Down

0 comments on commit def9ffc

Please sign in to comment.