Skip to content

Commit

Permalink
fix(behavior_tree_plugin) Fix isssue with pedestrian turning
Browse files Browse the repository at this point in the history
  • Loading branch information
SzymonParapura committed Dec 18, 2024
1 parent 0aae035 commit a213185
Show file tree
Hide file tree
Showing 4 changed files with 135 additions and 15 deletions.
33 changes: 33 additions & 0 deletions common/math/geometry/include/geometry/quaternion/norm.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// Copyright 2015 TIER IV, Inc. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GEOMETRY__QUATERNION__NORM_HPP_
#define GEOMETRY__QUATERNION__NORM_HPP_

#include <cmath>
#include <geometry/quaternion/is_like_quaternion.hpp>

namespace math
{
namespace geometry
{
template <typename T, std::enable_if_t<IsLikeQuaternion<T>::value, std::nullptr_t> = nullptr>
auto norm(const T & q)
{
return std::hypot(std::hypot(q.w, q.x), std::hypot(q.y, q.z));
}
} // namespace geometry
} // namespace math

#endif // GEOMETRY__QUATERNION__NORM_HPP_
43 changes: 43 additions & 0 deletions common/math/geometry/include/geometry/quaternion/normalize.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// Copyright 2015 TIER IV, Inc. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GEOMETRY__QUATERNION__NORMALIZE_HPP_
#define GEOMETRY__QUATERNION__NORMALIZE_HPP_

#include <geometry/quaternion/is_like_quaternion.hpp>
#include <geometry/quaternion/norm.hpp>
#include <geometry/quaternion/operator.hpp>
#include <scenario_simulator_exception/exception.hpp>

namespace math
{
namespace geometry
{
template <typename T, std::enable_if_t<IsLikeQuaternion<T>::value, std::nullptr_t> = nullptr>
auto normalize(const T & q)
{
const auto n = norm(q);
if (std::fabs(n) <= std::numeric_limits<double>::epsilon()) {
THROW_SIMULATION_ERROR(
"Norm of quaternion (", q.w, ",", q.x, ",", q.y, ",", q.z, ") is ", n,
". The norm of the quaternion you want to normalize should be greater than ",
std::numeric_limits<double>::epsilon());
}
return geometry_msgs::build<geometry_msgs::msg::Quaternion>().x(q.x / n).y(q.y / n).z(q.z / n).w(
q.w / n);
}
} // namespace geometry
} // namespace math

#endif // GEOMETRY__QUATERNION__NORMALIZE_HPP_
29 changes: 29 additions & 0 deletions common/math/geometry/include/geometry/quaternion/operator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define GEOMETRY__QUATERNION__OPERATOR_HPP_

#include <geometry/quaternion/is_like_quaternion.hpp>
#include <geometry/vector3/vector3.hpp>
#include <geometry_msgs/msg/quaternion.hpp>

namespace math
Expand Down Expand Up @@ -64,6 +65,34 @@ auto operator*(const T & a, const U & b)
return v;
}

template <
typename T, typename U,
std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>, IsLikeVector3<U>>, std::nullptr_t> =
nullptr>
auto operator*(const T & a, const U & b)
{
T b_quat;
b_quat.x = b.x;
b_quat.y = b.y;
b_quat.z = b.z;
b_quat.w = 0.0;

T a_inv = a;
a_inv.x = -a.x;
a_inv.y = -a.y;
a_inv.z = -a.z;
a_inv.w = a.w;

T result_quat = a * b_quat * a_inv;

U rotated_vector;
rotated_vector.x = result_quat.x;
rotated_vector.y = result_quat.y;
rotated_vector.z = result_quat.z;

return rotated_vector;
}

template <
typename T, typename U,
std::enable_if_t<std::conjunction_v<IsLikeQuaternion<T>, IsLikeQuaternion<U>>, std::nullptr_t> =
Expand Down
45 changes: 30 additions & 15 deletions simulation/behavior_tree_plugin/src/action_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <geometry/quaternion/euler_to_quaternion.hpp>
#include <geometry/quaternion/get_rotation.hpp>
#include <geometry/quaternion/get_rotation_matrix.hpp>
#include <geometry/quaternion/normalize.hpp>
#include <geometry/quaternion/quaternion_to_euler.hpp>
#include <geometry/vector3/normalize.hpp>
#include <memory>
Expand Down Expand Up @@ -516,23 +517,27 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame(
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);
const auto getEntityYaw = [&](const geometry_msgs::msg::Quaternion & orientation) {
return math::geometry::convertQuaternionToEulerAngle(orientation).z;
};

return lanelet_rpy.y;
const auto getLaneletPitch = [&](const lanelet::Id lanelet_id, const double s) {
return math::geometry::convertQuaternionToEulerAngle(
hdmap_utils->toMapOrientation(lanelet_id, s))
.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);
auto applyRotationToDisplacement = [&](
geometry_msgs::msg::Vector3 & displacement,
const double angle, const Eigen::Vector3d & axis) {
const Eigen::Quaterniond rotation(Eigen::AngleAxisd(angle, axis));
const Eigen::Vector3d rotated_displacement =
rotation * Eigen::Vector3d(displacement.x, displacement.y, displacement.z);

displacement.x = rotated_displacement.x();
displacement.y = rotated_displacement.y();
displacement.z = rotated_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(
Expand All @@ -544,7 +549,7 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame(
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 = canonicalized_entity_status->getMapPose();
const auto current_lanelet_Id = canonicalized_entity_status->getLaneletId();
static bool is_yaw_applied = false;

const auto desired_velocity = geometry_msgs::build<geometry_msgs::msg::Vector3>()
.x(twist_new.linear.x)
Expand All @@ -570,13 +575,23 @@ auto ActionNode::calculateUpdatedEntityStatusInWorldFrame(
};

if (!canonicalized_entity_status->laneMatchingSucceed()) {
displacement = math::geometry::normalize(pose_new.orientation) * displacement;
pose_new.position += displacement;

} else {
const auto current_lanelet_Id = canonicalized_entity_status->getLaneletId();
const auto lanelet_pose = canonicalized_entity_status->getLaneletPose().s;
applyPitchToDisplacement(displacement, getLaneletPitch(current_lanelet_Id, lanelet_pose));
applyRotationToDisplacement(
displacement, getLaneletPitch(current_lanelet_Id, lanelet_pose), Eigen::Vector3d::UnitY());
const double remaining_lanelet_length =
hdmap_utils->getLaneletLength(current_lanelet_Id) - lanelet_pose;

if (!is_yaw_applied) {
const double yaw = getEntityYaw(canonicalized_entity_status->getMapPose().orientation);
applyRotationToDisplacement(displacement, yaw, Eigen::Vector3d::UnitZ());
is_yaw_applied = true;
}

// 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);
Expand Down

0 comments on commit a213185

Please sign in to comment.