#include <cpp_scenario_node.hpp>
Inherits rclcpp::Node.
Inherited by RandomScenario, cpp_mock_scenarios::AccelerateAndFollowScenario, cpp_mock_scenarios::AcquirePositionInWorldFrameScenario, cpp_mock_scenarios::AcquireRouteInWorldFrameScenario, cpp_mock_scenarios::AutoSinkVehicleScenario, cpp_mock_scenarios::CancelRequestScenario, cpp_mock_scenarios::CrashingNpcScenario, cpp_mock_scenarios::DecelerateAndFollowScenario, cpp_mock_scenarios::DefineTrafficSourceDelay, cpp_mock_scenarios::DefineTrafficSourceHighRate, cpp_mock_scenarios::DefineTrafficSourceLarge, cpp_mock_scenarios::DefineTrafficSourceMixed, cpp_mock_scenarios::DefineTrafficSourceMultiple, cpp_mock_scenarios::DefineTrafficSourceOutsideLane, cpp_mock_scenarios::DefineTrafficSourcePedestrian, cpp_mock_scenarios::DefineTrafficSourceVehicle, cpp_mock_scenarios::FollowLaneWithOffsetScenario, cpp_mock_scenarios::FollowPolylineTrajectoryWithDoNothingPluginScenario, cpp_mock_scenarios::GetDistanceInLaneCoordinateScenario, cpp_mock_scenarios::GetDistanceToLaneBoundScenario, cpp_mock_scenarios::LaneChangeLeftScenario, cpp_mock_scenarios::LaneChangeLeftWithIdScenario, cpp_mock_scenarios::LaneChangeLinearLateralVelocityScenario, cpp_mock_scenarios::LaneChangeLinearScenario, cpp_mock_scenarios::LaneChangeLinearTimeScenario, cpp_mock_scenarios::LaneChangeLongitudinalDistanceScenario, cpp_mock_scenarios::LaneChangeRightScenario, cpp_mock_scenarios::LaneChangeRightWithIdScenario, cpp_mock_scenarios::LaneChangeTimeScenario, cpp_mock_scenarios::LoadDoNothingPluginScenario, cpp_mock_scenarios::MergeLeftScenario, cpp_mock_scenarios::MoveBackwardScenario, cpp_mock_scenarios::RequestSpeedChangeContinuousFalseScenario, cpp_mock_scenarios::RequestSpeedChangeRelativeScenario, cpp_mock_scenarios::RequestSpeedChangeScenario, cpp_mock_scenarios::RequestSpeedChangeStepScenario, cpp_mock_scenarios::RequestSpeedChangeWithLimitScenario, cpp_mock_scenarios::RequestSpeedChangeWithTimeConstraintLinearScenario, cpp_mock_scenarios::RequestSpeedChangeWithTimeConstraintRelativeScenario, cpp_mock_scenarios::RequestSpeedChangeWithTimeConstraintScenario, cpp_mock_scenarios::RespawnEgoScenario, cpp_mock_scenarios::SpawnInMapFrameScenario, cpp_mock_scenarios::SpawnWithOffsetScenario, cpp_mock_scenarios::StopAtCrosswalkScenario, cpp_mock_scenarios::SynchronizedAction, cpp_mock_scenarios::SynchronizedActionWithSpeed, cpp_mock_scenarios::TrafficSimulationDemoScenario, cpp_mock_scenarios::TraveledDistanceScenario, and cpp_mock_scenarios::WalkStraightScenario.
|
| CppScenarioNode (const std::string &node_name, const std::string &map_path, const std::string &lanelet2_map_file, const std::string &scenario_filename, const bool verbose, const rclcpp::NodeOptions &option, const std::set< std::uint8_t > &auto_sink_entity_types={}) |
|
void | start () |
|
void | stop (Result result, const std::string &description="") |
|
void | expectThrow () |
|
void | expectNoThrow () |
|
template<typename T > |
auto | equals (const T v1, const T v2, const T tolerance=std::numeric_limits< T >::epsilon()) const -> bool |
|
void | spawnEgoEntity (const traffic_simulator::CanonicalizedLaneletPose &spawn_lanelet_pose, const std::vector< traffic_simulator::CanonicalizedLaneletPose > &goal_lanelet_pose, const traffic_simulator_msgs::msg::VehicleParameters ¶meters) |
|
auto | isVehicle (const std::string &name) const -> bool |
|
auto | isPedestrian (const std::string &name) const -> bool |
|
◆ CppScenarioNode()
cpp_mock_scenarios::CppScenarioNode::CppScenarioNode |
( |
const std::string & |
node_name, |
|
|
const std::string & |
map_path, |
|
|
const std::string & |
lanelet2_map_file, |
|
|
const std::string & |
scenario_filename, |
|
|
const bool |
verbose, |
|
|
const rclcpp::NodeOptions & |
option, |
|
|
const std::set< std::uint8_t > & |
auto_sink_entity_types = {} |
|
) |
| |
|
explicit |
◆ equals()
template<typename T >
auto cpp_mock_scenarios::CppScenarioNode::equals |
( |
const T |
v1, |
|
|
const T |
v2, |
|
|
const T |
tolerance = std::numeric_limits<T>::epsilon() |
|
) |
| const -> bool
|
|
inline |
◆ expectNoThrow()
void cpp_mock_scenarios::CppScenarioNode::expectNoThrow |
( |
| ) |
|
|
inline |
◆ expectThrow()
void cpp_mock_scenarios::CppScenarioNode::expectThrow |
( |
| ) |
|
|
inline |
◆ isPedestrian()
auto cpp_mock_scenarios::CppScenarioNode::isPedestrian |
( |
const std::string & |
name | ) |
const -> bool |
◆ isVehicle()
auto cpp_mock_scenarios::CppScenarioNode::isVehicle |
( |
const std::string & |
name | ) |
const -> bool |
◆ spawnEgoEntity()
◆ start()
void cpp_mock_scenarios::CppScenarioNode::start |
( |
| ) |
|
◆ stop()
void cpp_mock_scenarios::CppScenarioNode::stop |
( |
Result |
result, |
|
|
const std::string & |
description = "" |
|
) |
| |
◆ api_
◆ junit_
The documentation for this class was generated from the following files: