Skip to content

Commit

Permalink
Change sign of slope acceleration and check canonicalization status i…
Browse files Browse the repository at this point in the history
…n acceleration calculation
  • Loading branch information
gmajrobotec committed Jan 19, 2025
1 parent 326fba4 commit ed55433
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -336,7 +336,7 @@ void EgoEntitySimulation::update(
`AutowareUniverse::getVehicleCommand`, and at the same time change
`acceleration` to a signed value.
*/
input(0) = gear_sign * (acceleration + acceleration_by_slope);
input(0) = gear_sign * acceleration + acceleration_by_slope;
input(1) = tire_angle;
break;

Expand Down Expand Up @@ -364,7 +364,7 @@ void EgoEntitySimulation::update(

auto EgoEntitySimulation::calculateAccelerationBySlope() const -> double
{
if (consider_acceleration_by_road_slope_) {
if (consider_acceleration_by_road_slope_ && status_.laneMatchingSucceed()) {
constexpr double gravity_acceleration = -9.81;
const double ego_pitch_angle =
math::geometry::convertQuaternionToEulerAngle(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,9 @@ class CanonicalizedEntityStatus
auto setLinearJerk(double) -> void;

auto laneMatchingSucceed() const noexcept -> bool;
auto getLaneletId() const noexcept -> lanelet::Id;
auto getLaneletId() const -> lanelet::Id;
auto getLaneletIds() const noexcept -> lanelet::Ids;
auto getLaneletPose() const noexcept -> const LaneletPose &;
auto getLaneletPose() const -> const LaneletPose &;
auto getCanonicalizedLaneletPose() const noexcept
-> const std::optional<CanonicalizedLaneletPose> &;
auto getName() const noexcept -> const std::string & { return entity_status_.name; }
Expand Down
4 changes: 2 additions & 2 deletions simulation/traffic_simulator/src/data_type/entity_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ auto CanonicalizedEntityStatus::getAltitude() const -> double
return entity_status_.pose.position.z;
}

auto CanonicalizedEntityStatus::getLaneletPose() const noexcept -> const LaneletPose &
auto CanonicalizedEntityStatus::getLaneletPose() const -> const LaneletPose &
{
if (canonicalized_lanelet_pose_) {
return canonicalized_lanelet_pose_->getLaneletPose();
Expand All @@ -136,7 +136,7 @@ auto CanonicalizedEntityStatus::getLaneletPose() const noexcept -> const Lanelet
}
}

auto CanonicalizedEntityStatus::getLaneletId() const noexcept -> lanelet::Id
auto CanonicalizedEntityStatus::getLaneletId() const -> lanelet::Id
{
return getLaneletPose().lanelet_id;
}
Expand Down

0 comments on commit ed55433

Please sign in to comment.