Skip to content
Open
Show file tree
Hide file tree
Changes from 82 commits
Commits
Show all changes
162 commits
Select commit Hold shift + click to select a range
02b9faf
remove horrors of &-captures
robomic Oct 30, 2024
6d626ac
extract distance_along_lanelet and discard_the_front_waypoint_and_rec…
robomic Oct 30, 2024
642d726
remove a scary-looking lambda
robomic Oct 30, 2024
e9baaea
further lambda extraction
robomic Oct 30, 2024
b573bf0
const PolylineTrajectory, lambda extraction
robomic Nov 6, 2024
ca13318
flatten if-statements
robomic Nov 7, 2024
ffedcb8
introduce a struct for follow_trajectory
robomic Nov 11, 2024
a442c8e
buildUpdatedEntityStatus
robomic Nov 11, 2024
d3213a7
validators
robomic Nov 12, 2024
9d895cb
PolylineTrajectoryFollower cleanup
robomic Nov 12, 2024
eba2168
add missing validator
robomic Nov 12, 2024
6bbba1e
remove dead code
robomic Nov 12, 2024
3958568
use const iterator
robomic Nov 12, 2024
ac535c3
inversion isfinite_vec3
robomic Nov 13, 2024
a5ed84d
typed and constexpr comparisons
robomic Nov 13, 2024
834fb3a
rename
robomic Nov 13, 2024
86471e7
typo
robomic Nov 13, 2024
572ea56
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Nov 13, 2024
3c82ceb
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Nov 14, 2024
c8dc98b
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Nov 14, 2024
cc2908c
inverse if-statement, specify captures
robomic Nov 14, 2024
6b2ba8b
Merge tag '5.3.2' into RJD-1388/follow_trajectory
robomic Nov 20, 2024
01ddaa9
reorder algorithm steps
robomic Nov 20, 2024
abba124
debug info
robomic Nov 20, 2024
edf1f6e
debug info
robomic Nov 20, 2024
a850510
mutable polyline_trajectory
robomic Nov 20, 2024
147b584
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Nov 21, 2024
7d12a12
acceleration validator
robomic Nov 21, 2024
0ec90b2
clean up FollowWaypointController
robomic Nov 22, 2024
26b87db
clean up FollowWaypointController
robomic Nov 22, 2024
179601d
noSnakeCase
robomic Nov 22, 2024
1c3e136
clarify comment
robomic Nov 22, 2024
6f25291
mutable iterators in std::rotate
robomic Nov 22, 2024
fe7c1ac
move
robomic Nov 22, 2024
18b3749
Merge tag '6.0.1' into RJD-1388/follow_trajectory
robomic Nov 27, 2024
41711f2
free function separation, condition simplification
robomic Nov 27, 2024
2f87d0b
Merge branch 'master' into RJD-1388/follow_trajectory
dmoszynski Dec 2, 2024
0bd75cd
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Dec 3, 2024
fb6fd7d
separation; EntityStatus validator/builder
robomic Dec 3, 2024
9abf110
recursion removal
robomic Dec 4, 2024
22791bf
line lint
robomic Dec 4, 2024
02470ff
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Dec 4, 2024
d07cca1
restructure polyline_trajectory namespace
robomic Dec 4, 2024
78e1f76
cleaner error throwing
robomic Dec 4, 2024
80547c9
refer to private untity_status_ field
robomic Dec 4, 2024
de3524c
special memeber function definitions
robomic Dec 4, 2024
b6ade20
dyn constraints assertions
robomic Dec 5, 2024
660f8c6
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Dec 5, 2024
a70d318
PolylineTrajectoryPositioner refactor
robomic Dec 5, 2024
f9bc647
spell check
robomic Dec 5, 2024
1075845
Fix ValidatedEntityStatus member initialization order
TauTheLepton Dec 18, 2024
d72ab82
Refactor ValidatedEntityStatus to use arguments instead of class members
TauTheLepton Dec 18, 2024
87e5581
Refactor ValidatedEntityStatus: step_time -> step_time_
TauTheLepton Dec 18, 2024
d9099ed
Refactor ValidatedEntityStatus: remove duplicated data: name
TauTheLepton Dec 18, 2024
b47dbeb
Refactor ValidatedEntityStatus: remove duplicated data: time
TauTheLepton Dec 18, 2024
8d7ca68
Refactor ValidatedEntityStatus: remove duplicated data: bounding_box
TauTheLepton Dec 18, 2024
24cf34f
Refactor ValidatedEntityStatus: remove duplicated data: lanelet_pose_…
TauTheLepton Dec 18, 2024
a79602a
Refactor ValidatedEntityStatus: remove duplicated data: position
TauTheLepton Dec 18, 2024
64bab33
Refactor ValidatedEntityStatus: remove duplicated data: linear_speed
TauTheLepton Dec 18, 2024
2eb721d
Refactor ValidatedEntityStatus: remove duplicated data: linear_accele…
TauTheLepton Dec 18, 2024
8b9369d
Refactor ValidatedEntityStatus: add orientation getter
TauTheLepton Dec 18, 2024
4b7b9a4
Refactor ValidatedEntityStatus: use position getter
TauTheLepton Dec 18, 2024
c4fd215
Fix position validation
TauTheLepton Dec 18, 2024
f5ba27a
Use getters
TauTheLepton Dec 18, 2024
b4b7cf2
Refactor ValidatedEntityStatus: add behavior parameter getter
TauTheLepton Dec 18, 2024
74e3591
Refactor ValidatedEntityStatus: add current velocity getter
TauTheLepton Dec 18, 2024
e12c4b0
Formatting of all getters
TauTheLepton Dec 18, 2024
96318b4
Make ValidatedEntityStatus data members private
TauTheLepton Dec 19, 2024
08c2505
Refactor: remove duplicated data: behavior_parameter
TauTheLepton Dec 19, 2024
b68d9bb
Refactor: remove pointless class PolylineTrajectoryFollower
TauTheLepton Dec 19, 2024
0b7b59a
Refactor: rename whole polyline_trajectory_follower directory + renam…
TauTheLepton Dec 19, 2024
251d94a
Refactor: rename whole polyline_trajectory_follower directory + renam…
TauTheLepton Dec 19, 2024
3cecfb1
Refactor PolylineTrajectoryPositioner & distance
TauTheLepton Dec 19, 2024
1ac46c4
Refactor PolylineTrajectoryPositioner: Style changes
TauTheLepton Dec 19, 2024
b3a28b5
Restore previous BehaviorPluginBase getter setter macro formatting th…
TauTheLepton Dec 19, 2024
d88cdd1
Merge pull request #1494 from tier4/RJD-1388/follow_trajectory_fix
robomic Dec 20, 2024
3b2a7c4
Merge branch 'RJD-1388/follow_trajectory' into RJD-1388/follow_trajec…
robomic Dec 20, 2024
a8e758b
Merge pull request #1495 from tier4/RJD-1388/follow_trajectory_update
robomic Dec 20, 2024
faeace9
Merge remote-tracking branch 'origin/master' into RJD-1388/follow_tra…
TauTheLepton Jan 7, 2025
ffcc0c0
Refactor: Use value_or
TauTheLepton Jan 7, 2025
3c07074
Refactor: Move initialization to if
TauTheLepton Jan 7, 2025
f91f80a
Refactor: Remove implicit conversion
TauTheLepton Jan 7, 2025
7b30cee
ref(traffic_simulator, geometry): add rotate and direction_to_quatern…
dmoszynski Jan 23, 2025
4c9ddd5
ref(traffic_simulator) : refactor/improve PolylineTrajectoryPositioner
dmoszynski Jan 24, 2025
310c306
ref(traffic_simulator): improve time_to_nerest and updateEntity in Po…
dmoszynski Jan 24, 2025
75b0472
ref(traffic_simulator): separate isNearestWaypointReachable in Polyli…
dmoszynski Jan 24, 2025
15f3a83
Revert trailing whitespace deletion
TauTheLepton Feb 12, 2025
436aba0
Pass HdMapUtils ptr as the last argument
TauTheLepton Feb 12, 2025
f542ffe
Get double type by value
TauTheLepton Feb 12, 2025
3173b3d
Revert previous condition
TauTheLepton Feb 12, 2025
520e005
Get double type by value
TauTheLepton Feb 12, 2025
4baf03d
Adjust code to pass HdMapUtils as the last argument
TauTheLepton Feb 12, 2025
c4ac964
Remove "magic values"
TauTheLepton Feb 12, 2025
ef1594c
Change the `distance::distanceAlongLanelet` to not have fallback into…
TauTheLepton Feb 12, 2025
3a9115e
Merge tag '10.0.0' into RJD-1388/follow_trajectory
robomic Feb 12, 2025
8a139f4
Adjust code to pass HdMapUtils as the last argument
TauTheLepton Feb 12, 2025
8119a99
spellcheck
robomic Feb 12, 2025
b58f5d4
Merge remote-tracking branch 'origin/RJD-1388/follow_trajectory' into…
TauTheLepton Feb 12, 2025
b8b503b
Merge remote-tracking branch 'origin/RJD-1388/follow_trajectory' into…
TauTheLepton Feb 12, 2025
54cfd44
Merge remote-tracking branch 'origin/master' into RJD-1388/follow_tra…
TauTheLepton Feb 12, 2025
00c3329
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Feb 13, 2025
edb0148
Merge tag '10.3.3' into RJD-1388/follow_trajectory
robomic Feb 19, 2025
b24d1de
Merge branch 'master' into RJD-1388/follow_trajectory
TauTheLepton Feb 20, 2025
a760e4b
Trigger SonarCloud
TauTheLepton Feb 20, 2025
9537ff8
Merge branch 'master' into RJD-1388/follow_trajectory
TauTheLepton Mar 6, 2025
c8194f4
resolve/update comments
robomic Mar 7, 2025
7002f41
Merge tag '12.1.2' into RJD-1388/follow_trajectory
robomic Mar 7, 2025
0be5866
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Mar 7, 2025
ca51fd5
Merge remote-tracking branch 'refs/remotes/origin/RJD-1388/follow_tra…
robomic Mar 7, 2025
5399a17
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Mar 11, 2025
ba43cf2
implement improvements/suggestions
robomic Mar 11, 2025
433f89c
Merge remote-tracking branch 'origin/RJD-1388/follow_trajectory' into…
robomic Mar 11, 2025
8877083
update comments
robomic Mar 12, 2025
30e865e
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Mar 12, 2025
19a1de3
merge 14.0.0
robomic Mar 17, 2025
1e83b87
code refinements
robomic Mar 17, 2025
da31345
Merge branch 'master' into RJD-1388/follow_trajectory
TauTheLepton May 6, 2025
b7c1ac2
Merge branch 'master' into RJD-1388/follow_trajectory
TauTheLepton May 12, 2025
b882ce2
merge master
robomic Jun 23, 2025
fcff1d1
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Jul 3, 2025
24d3885
FTA scenarios
robomic Jul 3, 2025
627ede3
endline
robomic Jul 3, 2025
9de47aa
fix distance inaccuracies
robomic Jul 11, 2025
ebc45c2
Merge tag '16.7.5' into RJD-1388/follow_trajectory
robomic Jul 11, 2025
455c75b
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Jul 18, 2025
d6eaa2f
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Jul 24, 2025
d8b4495
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Jul 28, 2025
1d56356
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Jul 30, 2025
23db0f2
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Aug 4, 2025
2209eeb
merge master
robomic Aug 13, 2025
0561734
merge master
robomic Aug 13, 2025
d244cb2
Merge branch 'master' into RJD-1388/follow_trajectory
takanotaiga Aug 22, 2025
ffb5c80
Merge branch 'master' into RJD-1388/follow_trajectory
takanotaiga Sep 5, 2025
4db4822
Implement yaw_flip noise for noise_v4
HansRobo Sep 12, 2025
f099e4c
rename noise.v4.<config_name>.rotation into noise.v4.<config_name>.yaw
HansRobo Sep 12, 2025
fba8c95
Add create_selector lambda function to make selector lambda more common
HansRobo Sep 16, 2025
912b969
commonize true positive calculation algorithm in noise_v2
HansRobo Sep 16, 2025
3cb59ef
use same true positive calculation algorithm to noise_v2 in noise_v4
HansRobo Sep 16, 2025
9127806
rename rotation to yaw in noise_v4
HansRobo Sep 16, 2025
d125095
Add missing parts for noise_v4
HansRobo Sep 16, 2025
b293464
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Sep 16, 2025
b067e4c
Implement yaw flip noise correctly
HansRobo Sep 16, 2025
da68681
Apply noise v4 correctly
HansRobo Sep 16, 2025
cd295f9
Merge branch 'master' into RJD-1388/follow_trajectory
takanotaiga Sep 17, 2025
042553b
use elliptical model for x,y,yaw in noise_v4
HansRobo Sep 18, 2025
013eedd
Update documentation for noise v4 parameters
HansRobo Sep 18, 2025
31b54ca
Merge branch 'master' into fix/noise_v4
HansRobo Sep 24, 2025
bff64de
Merge pull request #1685 from tier4/fix/noise_v4
HansRobo Sep 29, 2025
d3e5cc7
Bump version of scenario_simulator_v2 from version 17.5.3 to version …
actions-user Sep 29, 2025
a11ac14
Merge branch 'master' into RJD-1388/follow_trajectory
robomic Sep 29, 2025
3483426
port distanceAlongLanelet
robomic Sep 29, 2025
82b7275
Merge branch 'RJD-1388/follow_trajectory' of github.com:tier4/scenari…
robomic Sep 29, 2025
96c70af
Delete apt caches with space monitoring
HansRobo Oct 1, 2025
2baf7ce
delete build directory after colcon build
HansRobo Oct 1, 2025
f21c96e
use raw image in BuildAndRun.yaml
HansRobo Oct 1, 2025
ee8d3ef
use sudo with apt commands in BuildAndRun.yaml
HansRobo Oct 1, 2025
c527828
install libunwind-dev in BuildAndRun.yaml
HansRobo Oct 1, 2025
727420a
use sudo to remove apt caches in BuildAndRun.yaml
HansRobo Oct 1, 2025
c486ca2
use jlumbroso/free-disk-space in BuildAndRun.yaml
HansRobo Oct 2, 2025
0f5228d
Merge pull request #1689 from tier4/fix/no-space-left-on-device
HansRobo Oct 2, 2025
b02dc39
Bump version of scenario_simulator_v2 from version 17.6.0 to version …
actions-user Oct 2, 2025
b04a9d2
Merge branch 'master' into RJD-1388/follow_trajectory
HansRobo Oct 2, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -23,35 +23,27 @@ namespace math
namespace arithmetic
{
template <typename T>
auto isApproximatelyEqualTo(T a, T b)
constexpr auto isApproximatelyEqualTo(T a, T b) -> bool
{
return std::abs(a - b) <=
(std::numeric_limits<T>::epsilon() * std::max(std::abs(a), std::abs(b)));
}

template <typename T>
auto isEssentiallyEqualTo(T a, T b)
constexpr auto isEssentiallyEqualTo(T a, T b) -> bool
{
return std::abs(a - b) <=
(std::numeric_limits<T>::epsilon() * std::min(std::abs(a), std::abs(b)));
}

template <typename T, typename... Ts>
auto isDefinitelyLessThan(T a, T b, Ts... xs)
template <typename T>
constexpr auto isDefinitelyLessThan(T a, T b) -> bool
{
auto compare = [](T a, T b) {
return (b - a) > (std::numeric_limits<T>::epsilon() * std::max(std::abs(a), std::abs(b)));
};

if constexpr (0 < sizeof...(Ts)) {
return compare(a, b) and compare(b, xs...);
} else {
return compare(a, b);
}
return (b - a) > (std::numeric_limits<T>::epsilon() * std::max(std::abs(a), std::abs(b)));
}

template <typename T>
auto isDefinitelyGreaterThan(T a, T b)
constexpr auto isDefinitelyGreaterThan(T a, T b) -> bool
{
return (a - b) > (std::numeric_limits<T>::epsilon() * std::max(std::abs(a), std::abs(b)));
}
Expand Down
32 changes: 32 additions & 0 deletions common/math/geometry/include/geometry/vector3/is_finite.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// 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__VECTOR3__IS_FINITE_HPP_
#define GEOMETRY__VECTOR3__IS_FINITE_HPP_

#include <geometry/vector3/is_like_vector3.hpp>

namespace math
{
namespace geometry
{
template <typename T, std::enable_if_t<IsLikeVector3<T>::value, std::nullptr_t> = nullptr>
auto isFinite(const T & v) -> bool
{
return std::isfinite(v.x) and std::isfinite(v.y) and std::isfinite(v.z);
}
} // namespace geometry
} // namespace math

#endif // GEOMETRY__VECTOR3__IS_FINITE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <openscenario_interpreter/syntax/trajectory_following_mode.hpp>
#include <openscenario_interpreter/syntax/trajectory_ref.hpp>
#include <pugixml.hpp>
#include <traffic_simulator/behavior/follow_trajectory.hpp>
#include <traffic_simulator/behavior/follow_trajectory/follow_trajectory.hpp>

namespace openscenario_interpreter
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ auto FollowPolylineTrajectoryAction::providedPorts() -> BT::PortsList

auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus
{
auto getTargetSpeed = [&]() -> double {
const auto getTargetSpeed = [this]() -> double {
if (target_speed.has_value()) {
return target_speed.value();
} else {
Expand All @@ -74,11 +74,15 @@ auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus
THROW_SIMULATION_ERROR(
"Time in canonicalized_entity_status is NaN - FollowTrajectoryAction does not support such "
"case.");
} else if (
const auto entity_status_updated = traffic_simulator::follow_trajectory::makeUpdatedStatus(
static_cast<traffic_simulator::EntityStatus>(*canonicalized_entity_status),
*polyline_trajectory, behavior_parameter, hdmap_utils, step_time,
default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed())) {
} else if (const auto entity_status_updated =
traffic_simulator::follow_trajectory::makeUpdatedEntityStatus(
traffic_simulator::follow_trajectory::ValidatedEntityStatus(
static_cast<traffic_simulator::EntityStatus>(*canonicalized_entity_status),
behavior_parameter, step_time),
hdmap_utils, *polyline_trajectory,
default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed(),
step_time);
entity_status_updated.has_value()) {
setCanonicalizedEntityStatus(entity_status_updated.value());
setOutput("waypoints", calculateWaypoints());
setOutput("obstacle", calculateObstacle(calculateWaypoints()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ auto FollowPolylineTrajectoryAction::providedPorts() -> BT::PortsList

auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus
{
auto getTargetSpeed = [&]() -> double {
const auto getTargetSpeed = [this]() -> double {
if (target_speed.has_value()) {
return target_speed.value();
} else {
Expand All @@ -74,11 +74,15 @@ auto FollowPolylineTrajectoryAction::tick() -> BT::NodeStatus
THROW_SIMULATION_ERROR(
"Time in canonicalized_entity_status is NaN - FollowTrajectoryAction does not support such "
"case.");
} else if (
const auto entity_status_updated = traffic_simulator::follow_trajectory::makeUpdatedStatus(
static_cast<traffic_simulator::EntityStatus>(*canonicalized_entity_status),
*polyline_trajectory, behavior_parameter, hdmap_utils, step_time,
default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed())) {
} else if (const auto entity_status_updated =
traffic_simulator::follow_trajectory::makeUpdatedEntityStatus(
traffic_simulator::follow_trajectory::ValidatedEntityStatus(
static_cast<traffic_simulator::EntityStatus>(*canonicalized_entity_status),
behavior_parameter, step_time),
hdmap_utils, *polyline_trajectory,
default_matching_distance_for_lanelet_pose_calculation, getTargetSpeed(),
step_time);
entity_status_updated.has_value()) {
setCanonicalizedEntityStatus(entity_status_updated.value());
setOutput("waypoints", calculateWaypoints());
setOutput("obstacle", calculateObstacle(calculateWaypoints()));
Expand Down
6 changes: 4 additions & 2 deletions simulation/traffic_simulator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,10 @@ ament_auto_find_build_dependencies()

ament_auto_add_library(traffic_simulator SHARED
src/api/api.cpp
src/behavior/follow_trajectory.cpp
src/behavior/follow_waypoint_controller.cpp
src/behavior/follow_trajectory/follow_waypoint_controller.cpp
src/behavior/follow_trajectory/follow_trajectory.cpp
src/behavior/follow_trajectory/polyline_trajectory_positioner.cpp
src/behavior/follow_trajectory/validated_entity_status.cpp
src/behavior/longitudinal_speed_planning.cpp
src/behavior/route_planner.cpp
src/color_utils/color_utils.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <optional>
#include <string>
#include <traffic_simulator/behavior/follow_trajectory.hpp>
#include <traffic_simulator/behavior/follow_trajectory/follow_trajectory.hpp>
#include <traffic_simulator/data_type/behavior.hpp>
#include <traffic_simulator/data_type/entity_status.hpp>
#include <traffic_simulator/hdmap_utils/hdmap_utils.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,27 +12,31 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY_HPP_
#define TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY_HPP_
#ifndef TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_TRAJECTORY_HPP_
#define TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_TRAJECTORY_HPP_

#include <optional>
#include <traffic_simulator/behavior/follow_trajectory/follow_waypoint_controller.hpp>
#include <traffic_simulator/behavior/follow_trajectory/polyline_trajectory_positioner.hpp>
#include <traffic_simulator/behavior/follow_trajectory/validated_entity_status.hpp>
#include <traffic_simulator/data_type/entity_status.hpp>
#include <traffic_simulator/hdmap_utils/hdmap_utils.hpp>
#include <traffic_simulator_msgs/msg/behavior_parameter.hpp>
#include <traffic_simulator_msgs/msg/entity_status.hpp>
#include <traffic_simulator_msgs/msg/polyline_trajectory.hpp>

namespace traffic_simulator
{
namespace follow_trajectory
{
auto makeUpdatedStatus(
const traffic_simulator_msgs::msg::EntityStatus &,
traffic_simulator_msgs::msg::PolylineTrajectory &,
const traffic_simulator_msgs::msg::BehaviorParameter &,
const std::shared_ptr<hdmap_utils::HdMapUtils> &, double, double,
std::optional<double> target_speed = std::nullopt) -> std::optional<EntityStatus>;
/// @note side effects on polyline_trajectory
auto makeUpdatedEntityStatus(
const ValidatedEntityStatus & validated_entity_status,
const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr,
traffic_simulator_msgs::msg::PolylineTrajectory & polyline_trajectory,
const double matching_distance, const std::optional<double> target_speed, const double step_time)
-> std::optional<EntityStatus>;

} // namespace follow_trajectory
} // namespace traffic_simulator

#endif // TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY_HPP_
#endif // TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_TRAJECTORY_HPP_
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc. All rights reserved.
// 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.
Expand All @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_WAYPOINT_CONTROLLER_HPP_
#define TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_WAYPOINT_CONTROLLER_HPP_
#ifndef TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_WAYPOINT_CONTROLLER_HPP_
#define TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_WAYPOINT_CONTROLLER_HPP_

#include <algorithm>
#include <cmath>
Expand All @@ -30,11 +30,11 @@ namespace traffic_simulator
{
namespace follow_trajectory
{
struct ControllerError : public common::Error
struct ControllerError : public common::SimulationError
{
template <typename... Ts>
explicit ControllerError(Ts &&... xs)
: common::Error(common::concatenate(
: common::SimulationError(common::concatenate(
"An error occurred in the internal controller operation in the FollowTrajectoryAction. ",
"Please report the following information to the developer: ",
std::forward<decltype(xs)>(xs)...))
Expand All @@ -59,7 +59,7 @@ struct PredictedState

auto isImmobile(const double tolerance) const
{
return std::abs(speed) < tolerance && std::abs(acceleration) < tolerance;
return std::abs(speed) < tolerance and std::abs(acceleration) < tolerance;
}

template <typename StreamType>
Expand Down Expand Up @@ -129,7 +129,7 @@ class FollowWaypointController
There is no technical basis for this value, it was determined based on
Dawid Moszynski experiments.
*/
static constexpr std::size_t number_of_acceleration_candidates = 30;
static constexpr std::size_t number_of_acceleration_candidates = 30UL;

/*
This is a debugging method, it is not worth giving it much attention.
Expand Down Expand Up @@ -231,7 +231,7 @@ class FollowWaypointController
max_acceleration_rate{behavior_parameter.dynamic_constraints.max_acceleration_rate},
max_deceleration{behavior_parameter.dynamic_constraints.max_deceleration},
max_deceleration_rate{behavior_parameter.dynamic_constraints.max_deceleration_rate},
target_speed{(target_speed) ? target_speed.value() : max_speed}
target_speed{target_speed.value_or(max_speed)}
{
}

Expand All @@ -242,14 +242,14 @@ class FollowWaypointController
const traffic_simulator_msgs::msg::PolylineTrajectory & polyline_trajectory) const
-> std::string
{
if (const auto & vertices = polyline_trajectory.shape.vertices; !vertices.empty()) {
if (const auto & vertices = polyline_trajectory.shape.vertices; not vertices.empty()) {
std::stringstream waypoint_details;
waypoint_details << "Currently followed waypoint: ";

if (const auto first_waypoint_with_arrival_time_specified = std::find_if(
vertices.begin(), vertices.end(),
[](auto && vertex) { return not std::isnan(vertex.time); });
first_waypoint_with_arrival_time_specified !=
std::end(polyline_trajectory.shape.vertices)) {
vertices.cbegin(), vertices.cend(),
[](const auto & vertex) { return not std::isnan(vertex.time); });
first_waypoint_with_arrival_time_specified != vertices.cend()) {
waypoint_details << "[" << first_waypoint_with_arrival_time_specified->position.position.x
<< ", " << first_waypoint_with_arrival_time_specified->position.position.y
<< "] with specified time equal to "
Expand Down Expand Up @@ -288,13 +288,13 @@ class FollowWaypointController
const double speed) const -> double;

auto areConditionsOfArrivalMet(
const double acceleration, const double speed, const double distance) const -> double
const double acceleration, const double speed, const double distance) const -> bool
{
return (!with_breaking || std::abs(speed) < local_epsilon) &&
std::abs(acceleration) < local_epsilon && distance < finish_distance_tolerance;
return (not with_breaking or std::abs(speed) < local_epsilon) and
std::abs(acceleration) < local_epsilon and distance < finish_distance_tolerance;
}
};
} // namespace follow_trajectory
} // namespace traffic_simulator

#endif // TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_WAYPOINT_CONTROLLER_HPP_
#endif // TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__FOLLOW_WAYPOINT_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
// 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 TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__POLYLINE_TRAJECTORY_POSITIONER_HPP_
#define TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__POLYLINE_TRAJECTORY_POSITIONER_HPP_

#include <optional>
#include <traffic_simulator/behavior/follow_trajectory/follow_waypoint_controller.hpp>
#include <traffic_simulator/behavior/follow_trajectory/validated_entity_status.hpp>
#include <traffic_simulator/data_type/entity_status.hpp>
#include <traffic_simulator/hdmap_utils/hdmap_utils.hpp>
#include <traffic_simulator_msgs/msg/entity_status.hpp>
#include <traffic_simulator_msgs/msg/polyline_trajectory.hpp>

namespace traffic_simulator
{
namespace follow_trajectory
{

struct PolylineTrajectoryPositioner
{
public:
explicit PolylineTrajectoryPositioner(
const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr,
const ValidatedEntityStatus & validated_entity_status,
const traffic_simulator_msgs::msg::PolylineTrajectory & polyline_trajectory,
const std::optional<double> target_speed, const double matching_distance,
const double step_time);

auto makeUpdatedEntityStatus() const -> std::optional<EntityStatus>;

private:
const std::shared_ptr<hdmap_utils::HdMapUtils> hdmap_utils_ptr_;
const ValidatedEntityStatus validated_entity_status_;
const traffic_simulator_msgs::msg::PolylineTrajectory polyline_trajectory_;
const double step_time_;
const double matching_distance_;

const std::vector<traffic_simulator_msgs::msg::Vertex>::const_iterator
nearest_waypoint_with_specified_time_it_;
const geometry_msgs::msg::Point nearest_waypoint_position_;
const double distance_to_nearest_waypoint_;
const double total_remaining_distance_;
const double time_to_nearest_waypoint_;
const double total_remaining_time_;

const FollowWaypointController follow_waypoint_controller_;

auto totalRemainingDistance() const -> double;
auto totalRemainingTime() const noexcept(false) -> double;
auto isNearestWaypointWithSpecifiedTimeSameAsLastWaypoint() const -> bool;
auto nearestWaypointWithSpecifiedTimeIterator() const
-> std::vector<traffic_simulator_msgs::msg::Vertex>::const_iterator;
auto validatedEntityTargetPosition() const noexcept(false) -> geometry_msgs::msg::Point;
auto validatedEntityDesiredAcceleration() const noexcept(false) -> double;
auto validatedEntityDesiredVelocity(const double desired_speed) const noexcept(false)
-> geometry_msgs::msg::Vector3;
auto validatedEntityDesiredSpeed(const double desired_acceleration) const noexcept(false)
-> double;
auto validatePredictedState(const double desired_acceleration) const noexcept(false) -> void;
};
} // namespace follow_trajectory
} // namespace traffic_simulator

#endif // TRAFFIC_SIMULATOR__BEHAVIOR__FOLLOW_TRAJECTORY__POLYLINE_TRAJECTORY_POSITIONER_HPP_
Loading