dynamic_obs_msgs/DynObsTrajectory Message

File: dynamic_obs_msgs/DynObsTrajectory.msg

#a dynamic obstacle trajectory

#the probability of the obstacle following this trajectory
float64 probability

#whether this obstacle should be treated like a static obstacle at the end of its trajectory (true) 
#or the obstacle is ignored after the end of its trajectory (false)
bool exists_after

#the time parameterized path
geometry_msgs/PoseWithCovarianceStamped[] points

Expanded Definition

float64 probability
bool exists_after
geometry_msgs/PoseWithCovarianceStamped[] points
    Header header
        uint32 seq
        time stamp
        string frame_id
    geometry_msgs/PoseWithCovariance pose
        geometry_msgs/Pose pose
            geometry_msgs/Point position
                float64 x
                float64 y
                float64 z
            geometry_msgs/Quaternion orientation
                float64 x
                float64 y
                float64 z
                float64 w
        float64[36] covariance