scenario_simulator_v2 C++ API
Public Member Functions | List of all members
entity_behavior::DoNothingBehavior Class Reference

#include <plugin.hpp>

Inheritance diagram for entity_behavior::DoNothingBehavior:
Inheritance graph
[legend]
Collaboration diagram for entity_behavior::DoNothingBehavior:
Collaboration graph
[legend]

Public Member Functions

void update (double current_time, double step_time) override
 just update timestamp of entity_status_ member variable. More...
 
void configure (const rclcpp::Logger &logger) override
 setup rclcpp::logger for debug output, but there is no debug output in this plugin. More...
 
const std::string & getCurrentAction () const override
 Get the Current Action object. More...
 
std::vector< visualization_msgs::msg::Marker > getDebugMarker () override
 
void setDebugMarker (const std::vector< visualization_msgs::msg::Marker > &) override
 
double getDefaultMatchingDistanceForLaneletPoseCalculation () override
 
void setDefaultMatchingDistanceForLaneletPoseCalculation (const double &) override
 
std::vector< geometry_msgs::msg::Pose > getGoalPoses () override
 
void setGoalPoses (const std::vector< geometry_msgs::msg::Pose > &) override
 
traffic_simulator::lane_change::Parameter getLaneChangeParameters () override
 
void setLaneChangeParameters (const traffic_simulator::lane_change::Parameter &) override
 
std::optional< traffic_simulator_msgs::msg::Obstacle > getObstacle () override
 
void setObstacle (const std::optional< traffic_simulator_msgs::msg::Obstacle > &) override
 
EntityStatusDict getOtherEntityStatus () override
 
void setOtherEntityStatus (const EntityStatusDict &) override
 
traffic_simulator_msgs::msg::PedestrianParameters getPedestrianParameters () override
 
void setPedestrianParameters (const traffic_simulator_msgs::msg::PedestrianParameters &) override
 
std::shared_ptr< math::geometry::CatmullRomSplinegetReferenceTrajectory () override
 
void setReferenceTrajectory (const std::shared_ptr< math::geometry::CatmullRomSpline > &) override
 
lanelet::Ids getRouteLanelets () override
 
void setRouteLanelets (const lanelet::Ids &) override
 
std::optional< double > getTargetSpeed () override
 
void setTargetSpeed (const std::optional< double > &) override
 
std::shared_ptr< traffic_simulator::TrafficLightManagergetTrafficLightManager () override
 
void setTrafficLightManager (const std::shared_ptr< traffic_simulator::TrafficLightManager > &) override
 
traffic_simulator_msgs::msg::VehicleParameters getVehicleParameters () override
 
void setVehicleParameters (const traffic_simulator_msgs::msg::VehicleParameters &) override
 
traffic_simulator_msgs::msg::WaypointsArray getWaypoints () override
 
void setWaypoints (const traffic_simulator_msgs::msg::WaypointsArray &) override
 
traffic_simulator_msgs::msg::BehaviorParameter getBehaviorParameter () override
 
void setBehaviorParameter (const traffic_simulator_msgs::msg::BehaviorParameter &value) override
 
std::shared_ptr< traffic_simulator::CanonicalizedEntityStatusgetCanonicalizedEntityStatus () override
 
void setCanonicalizedEntityStatus (const std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > &value) override
 
double getCurrentTime () override
 
void setCurrentTime (const double &value) override
 
std::shared_ptr< hdmap_utils::HdMapUtilsgetHdMapUtils () override
 
void setHdMapUtils (const std::shared_ptr< hdmap_utils::HdMapUtils > &value) override
 
std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > getPolylineTrajectory () override
 
void setPolylineTrajectory (const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &value) override
 
traffic_simulator::behavior::Request getRequest () override
 
void setRequest (const traffic_simulator::behavior::Request &value) override
 
double getStepTime () override
 
void setStepTime (const double &value) override
 
- Public Member Functions inherited from entity_behavior::BehaviorPluginBase
virtual ~BehaviorPluginBase ()=default
 
auto getBehaviorParameterKey () const -> const std::string &
 
auto getCanonicalizedEntityStatusKey () const -> const std::string &
 
auto getCurrentTimeKey () const -> const std::string &
 
auto getDebugMarkerKey () const -> const std::string &
 
auto getDefaultMatchingDistanceForLaneletPoseCalculationKey () const -> const std::string &
 
auto getGoalPosesKey () const -> const std::string &
 
auto getHdMapUtilsKey () const -> const std::string &
 
auto getLaneChangeParametersKey () const -> const std::string &
 
auto getObstacleKey () const -> const std::string &
 
auto getOtherEntityStatusKey () const -> const std::string &
 
auto getPedestrianParametersKey () const -> const std::string &
 
auto getPolylineTrajectoryKey () const -> const std::string &
 
auto getReferenceTrajectoryKey () const -> const std::string &
 
auto getRequestKey () const -> const std::string &
 
auto getRouteLaneletsKey () const -> const std::string &
 
auto getStepTimeKey () const -> const std::string &
 
auto getTargetSpeedKey () const -> const std::string &
 
auto getTrafficLightManagerKey () const -> const std::string &
 
auto getVehicleParametersKey () const -> const std::string &
 
auto getWaypointsKey () const -> const std::string &
 

Member Function Documentation

◆ configure()

void entity_behavior::DoNothingBehavior::configure ( const rclcpp::Logger &  logger)
overridevirtual

setup rclcpp::logger for debug output, but there is no debug output in this plugin.

Parameters
loggerlogger for debug output, this argument exists for other BehaviorPlugin classes but are not used by this plugin.

Implements entity_behavior::BehaviorPluginBase.

◆ getBehaviorParameter()

traffic_simulator_msgs::msg::BehaviorParameter entity_behavior::DoNothingBehavior::getBehaviorParameter ( )
inlineoverridevirtual

◆ getCanonicalizedEntityStatus()

std::shared_ptr<traffic_simulator::CanonicalizedEntityStatus> entity_behavior::DoNothingBehavior::getCanonicalizedEntityStatus ( )
inlineoverridevirtual

◆ getCurrentAction()

const std::string & entity_behavior::DoNothingBehavior::getCurrentAction ( ) const
overridevirtual

Get the Current Action object.

Returns
const std::string& always return "do_nothing"

Implements entity_behavior::BehaviorPluginBase.

◆ getCurrentTime()

double entity_behavior::DoNothingBehavior::getCurrentTime ( )
inlineoverridevirtual

◆ getDebugMarker()

std::vector<visualization_msgs::msg::Marker> entity_behavior::DoNothingBehavior::getDebugMarker ( )
inlineoverridevirtual

◆ getDefaultMatchingDistanceForLaneletPoseCalculation()

double entity_behavior::DoNothingBehavior::getDefaultMatchingDistanceForLaneletPoseCalculation ( )
inlineoverridevirtual

◆ getGoalPoses()

std::vector<geometry_msgs::msg::Pose> entity_behavior::DoNothingBehavior::getGoalPoses ( )
inlineoverridevirtual

◆ getHdMapUtils()

std::shared_ptr<hdmap_utils::HdMapUtils> entity_behavior::DoNothingBehavior::getHdMapUtils ( )
inlineoverridevirtual

◆ getLaneChangeParameters()

traffic_simulator::lane_change::Parameter entity_behavior::DoNothingBehavior::getLaneChangeParameters ( )
inlineoverridevirtual

◆ getObstacle()

std::optional<traffic_simulator_msgs::msg::Obstacle> entity_behavior::DoNothingBehavior::getObstacle ( )
inlineoverridevirtual

◆ getOtherEntityStatus()

EntityStatusDict entity_behavior::DoNothingBehavior::getOtherEntityStatus ( )
inlineoverridevirtual

◆ getPedestrianParameters()

traffic_simulator_msgs::msg::PedestrianParameters entity_behavior::DoNothingBehavior::getPedestrianParameters ( )
inlineoverridevirtual

◆ getPolylineTrajectory()

std::shared_ptr<traffic_simulator_msgs::msg::PolylineTrajectory> entity_behavior::DoNothingBehavior::getPolylineTrajectory ( )
inlineoverridevirtual

◆ getReferenceTrajectory()

std::shared_ptr<math::geometry::CatmullRomSpline> entity_behavior::DoNothingBehavior::getReferenceTrajectory ( )
inlineoverridevirtual

◆ getRequest()

traffic_simulator::behavior::Request entity_behavior::DoNothingBehavior::getRequest ( )
inlineoverridevirtual

◆ getRouteLanelets()

lanelet::Ids entity_behavior::DoNothingBehavior::getRouteLanelets ( )
inlineoverridevirtual

◆ getStepTime()

double entity_behavior::DoNothingBehavior::getStepTime ( )
inlineoverridevirtual

◆ getTargetSpeed()

std::optional<double> entity_behavior::DoNothingBehavior::getTargetSpeed ( )
inlineoverridevirtual

◆ getTrafficLightManager()

std::shared_ptr<traffic_simulator::TrafficLightManager> entity_behavior::DoNothingBehavior::getTrafficLightManager ( )
inlineoverridevirtual

◆ getVehicleParameters()

traffic_simulator_msgs::msg::VehicleParameters entity_behavior::DoNothingBehavior::getVehicleParameters ( )
inlineoverridevirtual

◆ getWaypoints()

traffic_simulator_msgs::msg::WaypointsArray entity_behavior::DoNothingBehavior::getWaypoints ( )
inlineoverridevirtual

◆ setBehaviorParameter()

void entity_behavior::DoNothingBehavior::setBehaviorParameter ( const traffic_simulator_msgs::msg::BehaviorParameter &  value)
inlineoverridevirtual

◆ setCanonicalizedEntityStatus()

void entity_behavior::DoNothingBehavior::setCanonicalizedEntityStatus ( const std::shared_ptr< traffic_simulator::CanonicalizedEntityStatus > &  value)
inlineoverridevirtual

◆ setCurrentTime()

void entity_behavior::DoNothingBehavior::setCurrentTime ( const double &  value)
inlineoverridevirtual

◆ setDebugMarker()

void entity_behavior::DoNothingBehavior::setDebugMarker ( const std::vector< visualization_msgs::msg::Marker > &  )
inlineoverridevirtual

◆ setDefaultMatchingDistanceForLaneletPoseCalculation()

void entity_behavior::DoNothingBehavior::setDefaultMatchingDistanceForLaneletPoseCalculation ( const double &  )
inlineoverridevirtual

◆ setGoalPoses()

void entity_behavior::DoNothingBehavior::setGoalPoses ( const std::vector< geometry_msgs::msg::Pose > &  )
inlineoverridevirtual

◆ setHdMapUtils()

void entity_behavior::DoNothingBehavior::setHdMapUtils ( const std::shared_ptr< hdmap_utils::HdMapUtils > &  value)
inlineoverridevirtual

◆ setLaneChangeParameters()

void entity_behavior::DoNothingBehavior::setLaneChangeParameters ( const traffic_simulator::lane_change::Parameter )
inlineoverridevirtual

◆ setObstacle()

void entity_behavior::DoNothingBehavior::setObstacle ( const std::optional< traffic_simulator_msgs::msg::Obstacle > &  )
inlineoverridevirtual

◆ setOtherEntityStatus()

void entity_behavior::DoNothingBehavior::setOtherEntityStatus ( const EntityStatusDict )
inlineoverridevirtual

◆ setPedestrianParameters()

void entity_behavior::DoNothingBehavior::setPedestrianParameters ( const traffic_simulator_msgs::msg::PedestrianParameters &  )
inlineoverridevirtual

◆ setPolylineTrajectory()

void entity_behavior::DoNothingBehavior::setPolylineTrajectory ( const std::shared_ptr< traffic_simulator_msgs::msg::PolylineTrajectory > &  value)
inlineoverridevirtual

◆ setReferenceTrajectory()

void entity_behavior::DoNothingBehavior::setReferenceTrajectory ( const std::shared_ptr< math::geometry::CatmullRomSpline > &  )
inlineoverridevirtual

◆ setRequest()

void entity_behavior::DoNothingBehavior::setRequest ( const traffic_simulator::behavior::Request value)
inlineoverridevirtual

◆ setRouteLanelets()

void entity_behavior::DoNothingBehavior::setRouteLanelets ( const lanelet::Ids &  )
inlineoverridevirtual

◆ setStepTime()

void entity_behavior::DoNothingBehavior::setStepTime ( const double &  value)
inlineoverridevirtual

◆ setTargetSpeed()

void entity_behavior::DoNothingBehavior::setTargetSpeed ( const std::optional< double > &  )
inlineoverridevirtual

◆ setTrafficLightManager()

void entity_behavior::DoNothingBehavior::setTrafficLightManager ( const std::shared_ptr< traffic_simulator::TrafficLightManager > &  )
inlineoverridevirtual

◆ setVehicleParameters()

void entity_behavior::DoNothingBehavior::setVehicleParameters ( const traffic_simulator_msgs::msg::VehicleParameters &  )
inlineoverridevirtual

◆ setWaypoints()

void entity_behavior::DoNothingBehavior::setWaypoints ( const traffic_simulator_msgs::msg::WaypointsArray &  )
inlineoverridevirtual

◆ update()

void entity_behavior::DoNothingBehavior::update ( double  current_time,
double  step_time 
)
overridevirtual

just update timestamp of entity_status_ member variable.

Parameters
current_timecurrent time in scenario time
step_timestep time of the simulation, this argument exists for other BehaviorPlugin classes but are not used by this plugin.

Implements entity_behavior::BehaviorPluginBase.


The documentation for this class was generated from the following files: