diff --git a/simulation/behavior_tree_plugin/src/action_node.cpp b/simulation/behavior_tree_plugin/src/action_node.cpp index 86db4b18d41..3c69df7d004 100644 --- a/simulation/behavior_tree_plugin/src/action_node.cpp +++ b/simulation/behavior_tree_plugin/src/action_node.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -511,6 +512,28 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame( -> traffic_simulator::EntityStatus { using math::geometry::operator*; + using math::geometry::operator+; + using math::geometry::operator-; + using math::geometry::operator+=; + + const auto getLaneletPitch = [&](const lanelet::Id lanelet_id, const double s) { + const auto lanelet_orientation = hdmap_utils->toMapOrientation(lanelet_id, s); + const auto lanelet_rpy = math::geometry::convertQuaternionToEulerAngle(lanelet_orientation); + + return lanelet_rpy.y; + }; + + auto applyPitchToDisplacement = + [&](geometry_msgs::msg::Vector3 & displacement, const double pitch) { + const Eigen::Quaterniond pitch_rotation(Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY())); + const Eigen::Vector3d rotated_displacement = + pitch_rotation * Eigen::Vector3d(displacement.x, displacement.y, displacement.z); + + displacement.x = rotated_displacement.x(); + displacement.y = rotated_displacement.y(); + displacement.z = rotated_displacement.z(); + }; + const auto speed_planner = traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner( step_time, canonicalized_entity_status->getName()); @@ -520,21 +543,51 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame( double linear_jerk_new = std::get<2>(dynamics); geometry_msgs::msg::Accel accel_new = std::get<1>(dynamics); geometry_msgs::msg::Twist twist_new = std::get<0>(dynamics); - geometry_msgs::msg::Pose pose_new; - geometry_msgs::msg::Vector3 angular_trans_vec; - angular_trans_vec.z = twist_new.angular.z * step_time; - geometry_msgs::msg::Quaternion angular_trans_quat = - math::geometry::convertEulerAngleToQuaternion(angular_trans_vec); - pose_new.orientation = canonicalized_entity_status->getMapPose().orientation * angular_trans_quat; - Eigen::Vector3d trans_vec; - trans_vec(0) = twist_new.linear.x * step_time; - trans_vec(1) = twist_new.linear.y * step_time; - trans_vec(2) = 0; - Eigen::Matrix3d rotation_mat = math::geometry::getRotationMatrix(pose_new.orientation); - trans_vec = rotation_mat * trans_vec; - pose_new.position.x = trans_vec(0) + canonicalized_entity_status->getMapPose().position.x; - pose_new.position.y = trans_vec(1) + canonicalized_entity_status->getMapPose().position.y; - pose_new.position.z = trans_vec(2) + canonicalized_entity_status->getMapPose().position.z; + geometry_msgs::msg::Pose pose_new = canonicalized_entity_status->getMapPose(); + const auto current_lanelet_Id = canonicalized_entity_status->getLaneletId(); + + const auto desired_velocity = geometry_msgs::build() + .x(twist_new.linear.x) + .y(twist_new.linear.y) + .z(twist_new.linear.z); + auto displacement = desired_velocity * step_time; + + auto adjustPositionAtLaneletBoundary = + [&](double remaining_lanelet_length, const std::optional & next_lanelet_id) { + const auto excess_displacement = + displacement - math::geometry::normalize(desired_velocity) * remaining_lanelet_length; + + // Update position to the next lanelet if available, otherwise apply full displacement. + pose_new.position = next_lanelet_id + ? hdmap_utils->toMapPosition( + next_lanelet_id.value(), math::geometry::norm(excess_displacement)) + : pose_new.position + displacement; + + // Apply lateral offset if transitioning to the next lanelet + if (next_lanelet_id) { + pose_new.position.y += canonicalized_entity_status->getLaneletPose().offset; + } + }; + + if (!canonicalized_entity_status->laneMatchingSucceed()) { + pose_new.position += displacement; + } else { + const auto lanelet_pose = canonicalized_entity_status->getLaneletPose().s; + applyPitchToDisplacement(displacement, getLaneletPitch(current_lanelet_Id, lanelet_pose)); + const double remaining_lanelet_length = + hdmap_utils->getLaneletLength(current_lanelet_Id) - lanelet_pose; + + // Adjust position if displacement exceeds the current lanelet length. + if (math::geometry::norm(displacement) > remaining_lanelet_length) { + const auto next_lanelet_ids = hdmap_utils->getNextLaneletIds(current_lanelet_Id); + adjustPositionAtLaneletBoundary( + remaining_lanelet_length, + next_lanelet_ids.empty() ? std::nullopt : std::make_optional(next_lanelet_ids[0])); + } else { + pose_new.position += displacement; + } + } + auto entity_status_updated = static_cast(*canonicalized_entity_status); entity_status_updated.time = current_time + step_time; diff --git a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp index 82cb9eb8d71..9b804fd8290 100644 --- a/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp +++ b/simulation/traffic_simulator/include/traffic_simulator/hdmap_utils/hdmap_utils.hpp @@ -169,8 +169,8 @@ class HdMapUtils auto toMapPosition(const lanelet::Id lanelet_id, const double s) const -> geometry_msgs::msg::Point; - auto toMapOrientation(const lanelet::Id lanelet_id, const double s) const - -> geometry_msgs::msg::Quaternion; + auto toMapOrientation(const lanelet::Id lanelet_id, const double s, const bool fill_pitch = true) + const -> geometry_msgs::msg::Quaternion; auto getLaneChangeTrajectory( const geometry_msgs::msg::Pose & from, diff --git a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp index 562a0d67d3a..de6e9c92f68 100644 --- a/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp +++ b/simulation/traffic_simulator/src/hdmap_utils/hdmap_utils.cpp @@ -1118,10 +1118,11 @@ auto HdMapUtils::toMapPosition(const lanelet::Id lanelet_id, const double s) con return getCenterPointsSpline(lanelet_id)->getPoint(s); } -auto HdMapUtils::toMapOrientation(const lanelet::Id lanelet_id, const double s) const +auto HdMapUtils::toMapOrientation( + const lanelet::Id lanelet_id, const double s, const bool fill_pitch) const -> geometry_msgs::msg::Quaternion { - return getCenterPointsSpline(lanelet_id)->getPose(s, true).orientation; + return getCenterPointsSpline(lanelet_id)->getPose(s, fill_pitch).orientation; } auto HdMapUtils::getTrafficLightIds() const -> lanelet::Ids