Skip to content

Commit

Permalink
Merge pull request #1209 from tier4/feature/ego_slope
Browse files Browse the repository at this point in the history
Consider road slope in distance measurement and entity poses
  • Loading branch information
hakuturu583 authored Mar 12, 2024
2 parents 7ef5cdc + 918f2af commit ce8a77b
Show file tree
Hide file tree
Showing 39 changed files with 269 additions and 76 deletions.
5 changes: 5 additions & 0 deletions .github/workflows/SimModelUpdateNotification.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,11 @@ jobs:
notify:
runs-on: ubuntu-latest
steps:
- name: Checkout
uses: actions/checkout@v4
with:
fetch-depth: 0

- name: Add comment
run: |
gh pr comment "$PR_NUMBER" --edit-last --body "This PR edits vehicle model that is copied from [simple_planning_simulator](https://github.com/autowarefoundation/autoware.universe/tree/main/simulator/simple_planning_simulator). Please consider making changes to the original code to avoid confusion or consult developers (@hakuturu583, @yamacir-kit and @HansRobo )." \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ class LineSegment
const geometry_msgs::msg::Point end_point;
auto getPoint(const double s, const bool denormalize_s = false) const
-> geometry_msgs::msg::Point;
auto getPose(const double s, const bool denormalize_s = false) const -> geometry_msgs::msg::Pose;
auto getPose(const double s, const bool denormalize_s = false, const bool fill_pitch = true) const
-> geometry_msgs::msg::Pose;
auto isIntersect2D(const geometry_msgs::msg::Point & point) const -> bool;
auto isIntersect2D(const LineSegment & l0) const -> bool;
auto getIntersection2DSValue(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class CatmullRomSpline : public CatmullRomSplineInterface
auto getPoint(const double s, const double offset) const -> geometry_msgs::msg::Point;
auto getTangentVector(const double s) const -> geometry_msgs::msg::Vector3;
auto getNormalVector(const double s) const -> geometry_msgs::msg::Vector3;
auto getPose(const double s) const -> geometry_msgs::msg::Pose;
auto getPose(const double s, const bool fill_pitch = true) const -> geometry_msgs::msg::Pose;
auto getTrajectory(
const double start_s, const double end_s, const double resolution,
const double offset = 0.0) const -> std::vector<geometry_msgs::msg::Point>;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ class HermiteCurve
std::vector<geometry_msgs::msg::Point> getTrajectory(size_t num_points = 30) const;
const std::vector<geometry_msgs::msg::Point> getTrajectory(
double start_s, double end_s, double resolution, bool denormalize_s = false) const;
const geometry_msgs::msg::Pose getPose(double s, bool denormalize_s = false) const;
const geometry_msgs::msg::Pose getPose(
double s, bool denormalize_s = false, bool fill_pitch = true) const;
const geometry_msgs::msg::Point getPoint(double s, bool denormalize_s = false) const;
const geometry_msgs::msg::Vector3 getTangentVector(double s, bool denormalize_s = false) const;
const geometry_msgs::msg::Vector3 getNormalVector(double s, bool denormalize_s = false) const;
Expand Down
13 changes: 9 additions & 4 deletions common/math/geometry/src/polygon/line_segment.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,18 +93,23 @@ auto LineSegment::getPoint(const double s, const bool denormalize_s) const
* @brief Get pose on the line segment from s value. Orientation of thee return value was calculated from the vector of the line segment.
* @param s Normalized s value in coordinate along line segment.
* @param denormalize_s If true, s value should be normalized in range [0,1]. If false, s value is not normalized.
* @param fill_pitch If true, the pitch value of the orientation is filled. If false, the pitch value of the orientation is 0.
* This parameter is introduced for backward-compatibility.
* @return geometry_msgs::msg::Pose
*/
auto LineSegment::getPose(const double s, const bool denormalize_s) const
auto LineSegment::getPose(const double s, const bool denormalize_s, const bool fill_pitch) const
-> geometry_msgs::msg::Pose
{
return geometry_msgs::build<geometry_msgs::msg::Pose>()
.position(getPoint(s, denormalize_s))
.orientation([this]() -> geometry_msgs::msg::Quaternion {
.orientation([this, fill_pitch]() -> geometry_msgs::msg::Quaternion {
const auto tangent_vec = getVector();
return quaternion_operation::convertEulerAngleToQuaternion(
geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0.0).y(0.0).z(
std::atan2(tangent_vec.y, tangent_vec.x)));
geometry_msgs::build<geometry_msgs::msg::Vector3>()
.x(0.0)
.y(
fill_pitch ? std::atan2(-tangent_vec.z, std::hypot(tangent_vec.x, tangent_vec.y)) : 0.0)
.z(std::atan2(tangent_vec.y, tangent_vec.x)));
}());
}

Expand Down
7 changes: 4 additions & 3 deletions common/math/geometry/src/spline/catmull_rom_spline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -641,7 +641,8 @@ auto CatmullRomSpline::getTangentVector(const double s) const -> geometry_msgs::
}
}

auto CatmullRomSpline::getPose(const double s) const -> geometry_msgs::msg::Pose
auto CatmullRomSpline::getPose(const double s, const bool fill_pitch) const
-> geometry_msgs::msg::Pose
{
switch (control_points.size()) {
case 0:
Expand All @@ -664,10 +665,10 @@ auto CatmullRomSpline::getPose(const double s) const -> geometry_msgs::msg::Pose
"This message is not originally intended to be displayed, if you see it, please "
"contact the developer of traffic_simulator.");
}
return line_segments_[0].getPose(s, true);
return line_segments_[0].getPose(s, true, fill_pitch);
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getPose(index_and_s.second, true);
return curves_[index_and_s.first].getPose(index_and_s.second, true, fill_pitch);
}
}

Expand Down
6 changes: 4 additions & 2 deletions common/math/geometry/src/spline/hermite_curve.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -279,7 +279,9 @@ const geometry_msgs::msg::Vector3 HermiteCurve::getTangentVector(double s, bool
return vec;
}

const geometry_msgs::msg::Pose HermiteCurve::getPose(double s, bool denormalize_s) const
/// @note fill_pitch is introduced for backward-compatibility.
const geometry_msgs::msg::Pose HermiteCurve::getPose(
double s, bool denormalize_s, bool fill_pitch) const
{
if (denormalize_s) {
s = s / getLength();
Expand All @@ -288,7 +290,7 @@ const geometry_msgs::msg::Pose HermiteCurve::getPose(double s, bool denormalize_
geometry_msgs::msg::Vector3 tangent_vec = getTangentVector(s, false);
geometry_msgs::msg::Vector3 rpy;
rpy.x = 0.0;
rpy.y = 0.0;
rpy.y = fill_pitch ? std::atan2(-tangent_vec.z, std::hypot(tangent_vec.x, tangent_vec.y)) : 0.0;
rpy.z = std::atan2(tangent_vec.y, tangent_vec.x);
pose.orientation = quaternion_operation::convertEulerAngleToQuaternion(rpy);
pose.position = getPoint(s);
Expand Down
29 changes: 29 additions & 0 deletions common/math/geometry/test/test_catmull_rom_spline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,14 @@ math::geometry::CatmullRomSpline makeLine()
return math::geometry::CatmullRomSpline(points);
}

/// @brief Helper function generating sloped line: p(0,0,0)-> p(1,3,1) -> p(2,6,2)
math::geometry::CatmullRomSpline makeSlopedLine()
{
const std::vector<geometry_msgs::msg::Point> points{
makePoint(0.0, 0.0, 0.0), makePoint(1.0, 3.0, 1.0), makePoint(2.0, 6.0, 2.0)};
return math::geometry::CatmullRomSpline(points);
}

/// @brief Helper function generating curve: p(0,0)-> p(1,1)-> p(2,0)
math::geometry::CatmullRomSpline makeCurve()
{
Expand Down Expand Up @@ -465,6 +473,18 @@ TEST(CatmullRomSpline, getPoseLine)
quaternion_operation::convertEulerAngleToQuaternion(makeVector(0.0, 0.0, std::atan(3.0))), EPS);
}

TEST(CatmullRomSpline, getPoseLineWithPitch)
{
const math::geometry::CatmullRomSpline spline = makeSlopedLine();
const auto pose = spline.getPose(std::hypot(1.5, 4.5, 1.5), true);
EXPECT_POINT_NEAR(pose.position, makePoint(1.5, 4.5, 1.5), EPS);
EXPECT_QUATERNION_NEAR(
pose.orientation,
quaternion_operation::convertEulerAngleToQuaternion(
makeVector(0.0, std::atan2(-1.0, std::sqrt(1.0 + 3.0 * 3.0)), std::atan(3.0))),
EPS);
}

TEST(CatmullRomSpline, getPoseCurve)
{
const math::geometry::CatmullRomSpline spline = makeCurve();
Expand All @@ -474,6 +494,15 @@ TEST(CatmullRomSpline, getPoseCurve)
EXPECT_QUATERNION_NEAR(pose.orientation, geometry_msgs::msg::Quaternion(), eps);
}

TEST(CatmullRomSpline, getPoseCurveWithPitch)
{
const math::geometry::CatmullRomSpline spline = makeCurve();
const auto pose = spline.getPose(1.5, true);
constexpr double eps = 0.02;
EXPECT_POINT_NEAR(pose.position, makePoint(1.0, 1.0), eps);
EXPECT_QUATERNION_NEAR(pose.orientation, geometry_msgs::msg::Quaternion(), eps);
}

TEST(CatmullRomSpline, getSValue1)
{
const std::vector<geometry_msgs::msg::Point> points{
Expand Down
16 changes: 14 additions & 2 deletions common/math/geometry/test/test_line_segment.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,21 +387,33 @@ TEST(LineSegment, GetPose)
/// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis.
// [Snippet_getPose_with_s_0]
EXPECT_POSE_EQ(
line.getPose(0, false),
line.getPose(0, false, false),
geometry_msgs::build<geometry_msgs::msg::Pose>()
.position(geometry_msgs::build<geometry_msgs::msg::Point>().x(0).y(0).z(0))
.orientation(geometry_msgs::build<geometry_msgs::msg::Quaternion>().x(0).y(0).z(0).w(1)));
EXPECT_POSE_EQ(
line.getPose(0, false, true),
geometry_msgs::build<geometry_msgs::msg::Pose>()
.position(geometry_msgs::build<geometry_msgs::msg::Point>().x(0).y(0).z(0))
.orientation(quaternion_operation::convertEulerAngleToQuaternion(
geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0).y(-M_PI * 0.5).z(0))));
// [Snippet_getPose_with_s_0]
/// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_0

/// @note When the `s = 1`(1st argument of the `LineSegment::getPose` function), the return value of the `LineSegment::getPose` function should be an end point of the `line`.
/// Orientation should be defined by the direction of the `line`, so the orientation should be parallel to the z axis.
// [Snippet_getPose_with_s_1]
EXPECT_POSE_EQ(
line.getPose(1, false),
line.getPose(1, false, false),
geometry_msgs::build<geometry_msgs::msg::Pose>()
.position(geometry_msgs::build<geometry_msgs::msg::Point>().x(0).y(0).z(1))
.orientation(geometry_msgs::build<geometry_msgs::msg::Quaternion>().x(0).y(0).z(0).w(1)));
EXPECT_POSE_EQ(
line.getPose(1, false, true),
geometry_msgs::build<geometry_msgs::msg::Pose>()
.position(geometry_msgs::build<geometry_msgs::msg::Point>().x(0).y(0).z(1))
.orientation(quaternion_operation::convertEulerAngleToQuaternion(
geometry_msgs::build<geometry_msgs::msg::Vector3>().x(0).y(-M_PI * 0.5).z(0))));
// [Snippet_getPose_with_s_1]
/// @snippet test/test_line_segment.cpp Snippet_getPose_with_s_1
}
Expand Down
4 changes: 2 additions & 2 deletions external/concealer/src/autoware_universe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,8 +156,8 @@ auto AutowareUniverse::getGearCommand() const -> autoware_auto_vehicle_msgs::msg
auto AutowareUniverse::getGearSign() const -> double
{
using autoware_auto_vehicle_msgs::msg::GearCommand;
// @todo Add support for GearCommand::NONE to return 0.0
// @sa https://github.com/autowarefoundation/autoware.universe/blob/main/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L475
/// @todo Add support for GearCommand::NONE to return 0.0
/// @sa https://github.com/autowarefoundation/autoware.universe/blob/main/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L475
return getGearCommand().command == GearCommand::REVERSE or
getGearCommand().command == GearCommand::REVERSE_2
? -1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,8 @@ struct DistanceCondition : private Scope, private SimulatorCore::ConditionEvalua

std::vector<Double> results; // for description

const bool consider_z;

explicit DistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &);

auto description() const -> std::string;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace openscenario_interpreter
{
inline namespace syntax
{
/* ---- Position ---------------------------------------------------------------
/* ---- Position 1.2 -----------------------------------------------------------
*
* <xsd:complexType name="Position">
* <xsd:choice>
Expand All @@ -38,6 +38,8 @@ inline namespace syntax
* <xsd:element name="LanePosition" type="LanePosition"/>
* <xsd:element name="RelativeLanePosition" type="RelativeLanePosition"/>
* <xsd:element name="RoutePosition" type="RoutePosition"/>
* <xsd:element name="GeoPosition" type="GeoPosition" minOccurs="0"/>
* <xsd:element name="TrajectoryPosition" type="TrajectoryPosition" minOccurs="0"/>
* </xsd:choice>
* </xsd:complexType>
*
Expand All @@ -61,6 +63,8 @@ DEFINE_LAZY_VISITOR(
CASE(LanePosition),
// CASE(RelativeLanePosition),
// CASE(RoutePosition),
// CASE(GeoPosition),
// CASE(TrajectoryPosition),
);

DEFINE_LAZY_VISITOR(
Expand All @@ -73,6 +77,8 @@ DEFINE_LAZY_VISITOR(
CASE(LanePosition),
// CASE(RelativeLanePosition),
// CASE(RoutePosition),
// CASE(GeoPosition),
// CASE(TrajectoryPosition),
);
} // namespace syntax
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@ struct ReachPositionCondition : private SimulatorCore::CoordinateSystemConversio

std::vector<Double> results; // for description

const bool consider_z;

explicit ReachPositionCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &);

auto description() const -> String;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ struct RelativeDistanceCondition : private Scope, private SimulatorCore::Conditi

std::vector<Double> results; // for description

const bool consider_z;

explicit RelativeDistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &);

auto description() const -> String;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace openscenario_interpreter
{
inline namespace syntax
{
/* ---- WorldPosition ----------------------------------------------------------
/* ---- WorldPosition 1.2 ------------------------------------------------------
*
* <xsd:complexType name="WorldPosition">
* <xsd:attribute name="x" type="Double" use="required"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ auto AcquirePositionAction::start() -> void
{
const auto acquire_position = overload(
[](const WorldPosition & position, auto && actor) {
return applyAcquirePositionAction(actor, static_cast<geometry_msgs::msg::Pose>(position));
return applyAcquirePositionAction(actor, static_cast<NativeWorldPosition>(position));
},
[](const RelativeWorldPosition & position, auto && actor) {
return applyAcquirePositionAction(actor, static_cast<NativeLanePosition>(position));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <openscenario_interpreter/syntax/scenario_object.hpp>
#include <openscenario_interpreter/utility/overload.hpp>
#include <openscenario_interpreter/utility/print.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sstream>

// NOTE: Ignore spell miss due to OpenSCENARIO standard.
Expand All @@ -42,7 +43,12 @@ DistanceCondition::DistanceCondition(
value(readAttribute<Double>("value", node, scope)),
position(readElement<Position>("Position", node, scope)),
triggering_entities(triggering_entities),
results(triggering_entities.entity_refs.size(), Double::nan())
results(triggering_entities.entity_refs.size(), Double::nan()),
consider_z([]() {
rclcpp::Node node{"get_parameter", "simulation"};
node.declare_parameter("consider_pose_by_road_slope", false);
return node.get_parameter("consider_pose_by_road_slope").as_bool();
}())
{
}

Expand Down Expand Up @@ -101,6 +107,12 @@ auto DistanceCondition::distance(const EntityRef & triggering_entity) const -> d
return std::numeric_limits<double>::quiet_NaN();
}

// @todo: after checking all the scenario work well with consider_z = true, remove this function and use std::hypot(x,y,z)
static double hypot(const double x, const double y, const double z, const bool consider_z)
{
return consider_z ? std::hypot(x, y, z) : std::hypot(x, y);
}

template <>
auto DistanceCondition::distance<
CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, false>(
Expand All @@ -111,22 +123,30 @@ auto DistanceCondition::distance<
[&](const WorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const RelativeWorldPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const RelativeObjectPosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const LanePosition & position) {
const auto relative_world = makeNativeRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
}),
position);
}
Expand All @@ -141,22 +161,30 @@ auto DistanceCondition::distance<
[&](const WorldPosition & position) {
const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const RelativeWorldPosition & position) {
const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const RelativeObjectPosition & position) {
const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
},
[&](const LanePosition & position) {
const auto relative_world = makeNativeBoundingBoxRelativeWorldPosition(
triggering_entity, static_cast<NativeWorldPosition>(position));
return std::hypot(relative_world.position.x, relative_world.position.y);
return hypot(
relative_world.position.x, relative_world.position.y, relative_world.position.z,
consider_z);
}),
position);
}
Expand Down
Loading

0 comments on commit ce8a77b

Please sign in to comment.