#include <detection.h>
Public Types | |
typedef boost::array< float, 36 > | _covariances_type |
typedef int32_t | _id_type |
typedef ::geometry_msgs::Point_ < ContainerAllocator > | _position_type |
typedef float | _probability_type |
typedef ::geometry_msgs::Point_ < ContainerAllocator > | _velocity_type |
typedef boost::shared_ptr < ::iri_perception_msgs::detection_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::iri_perception_msgs::detection_ < ContainerAllocator > > | Ptr |
typedef detection_ < ContainerAllocator > | Type |
Public Member Functions | |
detection_ () | |
detection_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
boost::array< float, 36 > | covariances |
int32_t | id |
::geometry_msgs::Point_ < ContainerAllocator > | position |
float | probability |
::geometry_msgs::Point_ < ContainerAllocator > | velocity |
Definition at line 23 of file detection.h.
typedef boost::array<float, 36> iri_perception_msgs::detection_< ContainerAllocator >::_covariances_type |
Definition at line 52 of file detection.h.
typedef int32_t iri_perception_msgs::detection_< ContainerAllocator >::_id_type |
Definition at line 55 of file detection.h.
typedef ::geometry_msgs::Point_<ContainerAllocator> iri_perception_msgs::detection_< ContainerAllocator >::_position_type |
Definition at line 46 of file detection.h.
typedef float iri_perception_msgs::detection_< ContainerAllocator >::_probability_type |
Definition at line 58 of file detection.h.
typedef ::geometry_msgs::Point_<ContainerAllocator> iri_perception_msgs::detection_< ContainerAllocator >::_velocity_type |
Definition at line 49 of file detection.h.
typedef boost::shared_ptr< ::iri_perception_msgs::detection_<ContainerAllocator> const> iri_perception_msgs::detection_< ContainerAllocator >::ConstPtr |
Definition at line 63 of file detection.h.
typedef boost::shared_ptr< ::iri_perception_msgs::detection_<ContainerAllocator> > iri_perception_msgs::detection_< ContainerAllocator >::Ptr |
Definition at line 62 of file detection.h.
typedef detection_<ContainerAllocator> iri_perception_msgs::detection_< ContainerAllocator >::Type |
Definition at line 24 of file detection.h.
iri_perception_msgs::detection_< ContainerAllocator >::detection_ | ( | ) | [inline] |
Definition at line 26 of file detection.h.
iri_perception_msgs::detection_< ContainerAllocator >::detection_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 36 of file detection.h.
boost::shared_ptr<std::map<std::string, std::string> > iri_perception_msgs::detection_< ContainerAllocator >::__connection_header |
Definition at line 64 of file detection.h.
boost::array<float, 36> iri_perception_msgs::detection_< ContainerAllocator >::covariances |
Definition at line 53 of file detection.h.
int32_t iri_perception_msgs::detection_< ContainerAllocator >::id |
Definition at line 56 of file detection.h.
::geometry_msgs::Point_<ContainerAllocator> iri_perception_msgs::detection_< ContainerAllocator >::position |
Definition at line 47 of file detection.h.
float iri_perception_msgs::detection_< ContainerAllocator >::probability |
Definition at line 59 of file detection.h.
::geometry_msgs::Point_<ContainerAllocator> iri_perception_msgs::detection_< ContainerAllocator >::velocity |
Definition at line 50 of file detection.h.