Autoware.Auto
autoware::prediction Namespace Reference

Namespaces

 test
 

Classes

class  Parameters
 
class  PredictionNode
 Main node for prediction of dynamic objects. More...
 

Functions

geometry_msgs::msg::PoseWithCovariance LONELY_WORLD_PREDICTION_PUBLIC make_pose (const autoware_auto_perception_msgs::msg::TrackedObjectKinematics &tracked)
 
autoware_auto_perception_msgs::msg::PredictedObjects LONELY_WORLD_PREDICTION_PUBLIC from_tracked (const autoware_auto_perception_msgs::msg::TrackedObjects &objects)
 Create one PredictedObject from each TrackedObject and copy over all members that are common, leaving the predicted_paths member empty. More...
 
autoware_auto_perception_msgs::msg::PredictedObject LONELY_WORLD_PREDICTION_PUBLIC from_tracked (const autoware_auto_perception_msgs::msg::TrackedObject &object)
 Create a PredictedObject from a TrackedObject and copy over all members that are common, leaving the predicted_paths member empty. More...
 
autoware_auto_perception_msgs::msg::PredictedObjectKinematics LONELY_WORLD_PREDICTION_PUBLIC from_tracked (const autoware_auto_perception_msgs::msg::TrackedObjectKinematics &kinematics)
 Create PredictedObjectKinematics from TrackedObjectKinematics and copy over all members that are common, leaving the predicted_paths member empty. More...
 
void LONELY_WORLD_PREDICTION_PUBLIC predict_stationary (autoware_auto_perception_msgs::msg::PredictedObject &predicted_object, const autoware::prediction::Parameters &parameters)
 Predict object to remain stationary. More...
 
void LONELY_WORLD_PREDICTION_PUBLIC predict_stationary (autoware_auto_perception_msgs::msg::PredictedObjects &predicted_objects, const autoware::prediction::Parameters &parameters)
 Predict all input objects to remain stationary. More...
 

Function Documentation

◆ from_tracked() [1/3]

autoware_auto_perception_msgs::msg::PredictedObject autoware::prediction::from_tracked ( const autoware_auto_perception_msgs::msg::TrackedObject &  object)

Create a PredictedObject from a TrackedObject and copy over all members that are common, leaving the predicted_paths member empty.

Parameters
[in]objectInput tracked object
Returns
predicted object

◆ from_tracked() [2/3]

autoware_auto_perception_msgs::msg::PredictedObjectKinematics autoware::prediction::from_tracked ( const autoware_auto_perception_msgs::msg::TrackedObjectKinematics &  kinematics)

Create PredictedObjectKinematics from TrackedObjectKinematics and copy over all members that are common, leaving the predicted_paths member empty.

Parameters
[in]kinematicsInput kinematics
Returns
predicted objects

◆ from_tracked() [3/3]

autoware_auto_perception_msgs::msg::PredictedObjects autoware::prediction::from_tracked ( const autoware_auto_perception_msgs::msg::TrackedObjects &  objects)

Create one PredictedObject from each TrackedObject and copy over all members that are common, leaving the predicted_paths member empty.

Parameters
[in]objectsInput tracked objects
Returns
predicted objects

◆ make_pose()

geometry_msgs::msg::PoseWithCovariance autoware::prediction::make_pose ( const autoware_auto_perception_msgs::msg::TrackedObjectKinematics &  tracked)

◆ predict_stationary() [1/2]

void autoware::prediction::predict_stationary ( autoware_auto_perception_msgs::msg::PredictedObject &  predicted_object,
const autoware::prediction::Parameters parameters 
)

Predict object to remain stationary.

Stationary means that all predicted states have:

  • pose = initial pose

The initial velocity and acceleration are unmodified and may be nonzero

Parameters
[in,out]predicted_objectContains the path on return
[in]parametersDefine time step and time horizon of path. The last predicted state is after the time_horizon if time_step divides time_horizon with a remainder.

◆ predict_stationary() [2/2]

void autoware::prediction::predict_stationary ( autoware_auto_perception_msgs::msg::PredictedObjects &  predicted_objects,
const autoware::prediction::Parameters parameters 
)

Predict all input objects to remain stationary.

See also
predict_stationary() for details how each object is predicted
Parameters
[in,out]predicted_objects
[in]parameters