Public Types | Public Member Functions | Public Attributes | List of all members
sick_scan_xd::RadarObject_< ContainerAllocator > Struct Template Reference

#include <RadarObject.h>

Public Types

typedef ::geometry_msgs::Pose_< ContainerAllocator > _bounding_box_center_type
 
typedef ::geometry_msgs::Vector3_< ContainerAllocator > _bounding_box_size_type
 
typedef std::vector< ::geometry_msgs::Point_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::geometry_msgs::Point_< ContainerAllocator > >::other > _contour_points_type
 
typedef int32_t _id_type
 
typedef ros::Time _last_seen_type
 
typedef ::geometry_msgs::PoseWithCovariance_< ContainerAllocator > _object_box_center_type
 
typedef ::geometry_msgs::Vector3_< ContainerAllocator > _object_box_size_type
 
typedef ros::Time _tracking_time_type
 
typedef ::geometry_msgs::TwistWithCovariance_< ContainerAllocator > _velocity_type
 
typedef std::shared_ptr< ::sick_scan_xd::RadarObject_< ContainerAllocator > constConstPtr
 
typedef std::shared_ptr< ::sick_scan_xd::RadarObject_< ContainerAllocator > > Ptr
 
typedef RadarObject_< ContainerAllocator > Type
 

Public Member Functions

 RadarObject_ ()
 
 RadarObject_ (const ContainerAllocator &_alloc)
 

Public Attributes

_bounding_box_center_type bounding_box_center
 
_bounding_box_size_type bounding_box_size
 
_contour_points_type contour_points
 
_id_type id
 
_last_seen_type last_seen
 
_object_box_center_type object_box_center
 
_object_box_size_type object_box_size
 
_tracking_time_type tracking_time
 
_velocity_type velocity
 

Detailed Description

template<class ContainerAllocator>
struct sick_scan_xd::RadarObject_< ContainerAllocator >

Definition at line 29 of file RadarObject.h.

Member Typedef Documentation

◆ _bounding_box_center_type

template<class ContainerAllocator >
typedef ::geometry_msgs::Pose_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::_bounding_box_center_type

Definition at line 71 of file RadarObject.h.

◆ _bounding_box_size_type

template<class ContainerAllocator >
typedef ::geometry_msgs::Vector3_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::_bounding_box_size_type

Definition at line 74 of file RadarObject.h.

◆ _contour_points_type

template<class ContainerAllocator >
typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > sick_scan_xd::RadarObject_< ContainerAllocator >::_contour_points_type

Definition at line 83 of file RadarObject.h.

◆ _id_type

template<class ContainerAllocator >
typedef int32_t sick_scan_xd::RadarObject_< ContainerAllocator >::_id_type

Definition at line 59 of file RadarObject.h.

◆ _last_seen_type

template<class ContainerAllocator >
typedef ros::Time sick_scan_xd::RadarObject_< ContainerAllocator >::_last_seen_type

Definition at line 65 of file RadarObject.h.

◆ _object_box_center_type

template<class ContainerAllocator >
typedef ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::_object_box_center_type

Definition at line 77 of file RadarObject.h.

◆ _object_box_size_type

template<class ContainerAllocator >
typedef ::geometry_msgs::Vector3_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::_object_box_size_type

Definition at line 80 of file RadarObject.h.

◆ _tracking_time_type

template<class ContainerAllocator >
typedef ros::Time sick_scan_xd::RadarObject_< ContainerAllocator >::_tracking_time_type

Definition at line 62 of file RadarObject.h.

◆ _velocity_type

template<class ContainerAllocator >
typedef ::geometry_msgs::TwistWithCovariance_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::_velocity_type

Definition at line 68 of file RadarObject.h.

◆ ConstPtr

template<class ContainerAllocator >
typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator> const> sick_scan_xd::RadarObject_< ContainerAllocator >::ConstPtr

Definition at line 91 of file RadarObject.h.

◆ Ptr

template<class ContainerAllocator >
typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator> > sick_scan_xd::RadarObject_< ContainerAllocator >::Ptr

Definition at line 90 of file RadarObject.h.

◆ Type

template<class ContainerAllocator >
typedef RadarObject_<ContainerAllocator> sick_scan_xd::RadarObject_< ContainerAllocator >::Type

Definition at line 31 of file RadarObject.h.

Constructor & Destructor Documentation

◆ RadarObject_() [1/2]

template<class ContainerAllocator >
sick_scan_xd::RadarObject_< ContainerAllocator >::RadarObject_ ( )
inline

Definition at line 33 of file RadarObject.h.

◆ RadarObject_() [2/2]

template<class ContainerAllocator >
sick_scan_xd::RadarObject_< ContainerAllocator >::RadarObject_ ( const ContainerAllocator &  _alloc)
inline

Definition at line 44 of file RadarObject.h.

Member Data Documentation

◆ bounding_box_center

template<class ContainerAllocator >
_bounding_box_center_type sick_scan_xd::RadarObject_< ContainerAllocator >::bounding_box_center

Definition at line 72 of file RadarObject.h.

◆ bounding_box_size

template<class ContainerAllocator >
_bounding_box_size_type sick_scan_xd::RadarObject_< ContainerAllocator >::bounding_box_size

Definition at line 75 of file RadarObject.h.

◆ contour_points

template<class ContainerAllocator >
_contour_points_type sick_scan_xd::RadarObject_< ContainerAllocator >::contour_points

Definition at line 84 of file RadarObject.h.

◆ id

template<class ContainerAllocator >
_id_type sick_scan_xd::RadarObject_< ContainerAllocator >::id

Definition at line 60 of file RadarObject.h.

◆ last_seen

template<class ContainerAllocator >
_last_seen_type sick_scan_xd::RadarObject_< ContainerAllocator >::last_seen

Definition at line 66 of file RadarObject.h.

◆ object_box_center

template<class ContainerAllocator >
_object_box_center_type sick_scan_xd::RadarObject_< ContainerAllocator >::object_box_center

Definition at line 78 of file RadarObject.h.

◆ object_box_size

template<class ContainerAllocator >
_object_box_size_type sick_scan_xd::RadarObject_< ContainerAllocator >::object_box_size

Definition at line 81 of file RadarObject.h.

◆ tracking_time

template<class ContainerAllocator >
_tracking_time_type sick_scan_xd::RadarObject_< ContainerAllocator >::tracking_time

Definition at line 63 of file RadarObject.h.

◆ velocity

template<class ContainerAllocator >
_velocity_type sick_scan_xd::RadarObject_< ContainerAllocator >::velocity

Definition at line 69 of file RadarObject.h.


The documentation for this struct was generated from the following file:


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:21