$search
#include <LaserScan.h>
Public Types | |
| typedef float | _angle_increment_type |
| typedef float | _angle_max_type |
| typedef float | _angle_min_type |
| typedef ::std_msgs::Header_ < ContainerAllocator > | _header_type |
| typedef std::vector< float, typename ContainerAllocator::template rebind< float >::other > | _intensities_type |
| typedef float | _range_max_type |
| typedef float | _range_min_type |
| typedef std::vector< float, typename ContainerAllocator::template rebind< float >::other > | _ranges_type |
| typedef float | _scan_time_type |
| typedef float | _time_increment_type |
| typedef boost::shared_ptr < ::sensor_msgs::LaserScan_ < ContainerAllocator > const > | ConstPtr |
| typedef boost::shared_ptr < ::sensor_msgs::LaserScan_ < ContainerAllocator > > | Ptr |
| typedef LaserScan_ < ContainerAllocator > | Type |
Public Member Functions | |
| ROS_DEPRECATED const std::string | __getDataType () const |
| ROS_DEPRECATED const std::string | __getMD5Sum () const |
| ROS_DEPRECATED const std::string | __getMessageDefinition () const |
| virtual ROS_DEPRECATED uint8_t * | deserialize (uint8_t *read_ptr) |
| ROS_DEPRECATED uint32_t | get_intensities_size () const |
| ROS_DEPRECATED void | get_intensities_vec (std::vector< float, typename ContainerAllocator::template rebind< float >::other > &vec) const |
| ROS_DEPRECATED uint32_t | get_ranges_size () const |
| ROS_DEPRECATED void | get_ranges_vec (std::vector< float, typename ContainerAllocator::template rebind< float >::other > &vec) const |
| LaserScan_ (const ContainerAllocator &_alloc) | |
| LaserScan_ () | |
| virtual ROS_DEPRECATED uint32_t | serializationLength () const |
| virtual ROS_DEPRECATED uint8_t * | serialize (uint8_t *write_ptr, uint32_t seq) const |
| ROS_DEPRECATED void | set_intensities_size (uint32_t size) |
| ROS_DEPRECATED void | set_intensities_vec (const std::vector< float, typename ContainerAllocator::template rebind< float >::other > &vec) |
| ROS_DEPRECATED void | set_ranges_size (uint32_t size) |
| ROS_DEPRECATED void | set_ranges_vec (const std::vector< float, typename ContainerAllocator::template rebind< float >::other > &vec) |
Static Public Member Functions | |
| static ROS_DEPRECATED const std::string | __s_getDataType () |
| static ROS_DEPRECATED const std::string | __s_getMD5Sum () |
| static ROS_DEPRECATED const std::string | __s_getMessageDefinition () |
Public Attributes | |
| boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
| float | angle_increment |
| float | angle_max |
| float | angle_min |
| ::std_msgs::Header_ < ContainerAllocator > | header |
| std::vector< float, typename ContainerAllocator::template rebind< float >::other > | intensities |
| float | range_max |
| float | range_min |
| std::vector< float, typename ContainerAllocator::template rebind< float >::other > | ranges |
| float | scan_time |
| float | time_increment |
Static Private Member Functions | |
| static const char * | __s_getDataType_ () |
| static const char * | __s_getMD5Sum_ () |
| static const char * | __s_getMessageDefinition_ () |
Definition at line 22 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_angle_increment_type |
Definition at line 62 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_angle_max_type |
Definition at line 59 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_angle_min_type |
Definition at line 56 of file LaserScan.h.
| typedef ::std_msgs::Header_<ContainerAllocator> sensor_msgs::LaserScan_< ContainerAllocator >::_header_type |
Definition at line 53 of file LaserScan.h.
| typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > sensor_msgs::LaserScan_< ContainerAllocator >::_intensities_type |
Definition at line 80 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_range_max_type |
Definition at line 74 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_range_min_type |
Definition at line 71 of file LaserScan.h.
| typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > sensor_msgs::LaserScan_< ContainerAllocator >::_ranges_type |
Definition at line 77 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_scan_time_type |
Definition at line 68 of file LaserScan.h.
| typedef float sensor_msgs::LaserScan_< ContainerAllocator >::_time_increment_type |
Definition at line 65 of file LaserScan.h.
| typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> const> sensor_msgs::LaserScan_< ContainerAllocator >::ConstPtr |
Definition at line 210 of file LaserScan.h.
| typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> > sensor_msgs::LaserScan_< ContainerAllocator >::Ptr |
Definition at line 209 of file LaserScan.h.
| typedef LaserScan_<ContainerAllocator> sensor_msgs::LaserScan_< ContainerAllocator >::Type |
Definition at line 23 of file LaserScan.h.
| sensor_msgs::LaserScan_< ContainerAllocator >::LaserScan_ | ( | ) | [inline] |
Definition at line 25 of file LaserScan.h.
| sensor_msgs::LaserScan_< ContainerAllocator >::LaserScan_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 39 of file LaserScan.h.
| ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__getDataType | ( | ) | const [inline] |
Definition at line 97 of file LaserScan.h.
| ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__getMD5Sum | ( | ) | const [inline] |
Definition at line 104 of file LaserScan.h.
| ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__getMessageDefinition | ( | ) | const [inline] |
Definition at line 159 of file LaserScan.h.
| static ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__s_getDataType | ( | ) | [inline, static] |
Definition at line 95 of file LaserScan.h.
| static const char* sensor_msgs::LaserScan_< ContainerAllocator >::__s_getDataType_ | ( | ) | [inline, static, private] |
Definition at line 93 of file LaserScan.h.
| static ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__s_getMD5Sum | ( | ) | [inline, static] |
Definition at line 102 of file LaserScan.h.
| static const char* sensor_msgs::LaserScan_< ContainerAllocator >::__s_getMD5Sum_ | ( | ) | [inline, static, private] |
Definition at line 100 of file LaserScan.h.
| static ROS_DEPRECATED const std::string sensor_msgs::LaserScan_< ContainerAllocator >::__s_getMessageDefinition | ( | ) | [inline, static] |
Definition at line 157 of file LaserScan.h.
| static const char* sensor_msgs::LaserScan_< ContainerAllocator >::__s_getMessageDefinition_ | ( | ) | [inline, static, private] |
Definition at line 107 of file LaserScan.h.
| virtual ROS_DEPRECATED uint8_t* sensor_msgs::LaserScan_< ContainerAllocator >::deserialize | ( | uint8_t * | read_ptr | ) | [inline, virtual] |
Definition at line 177 of file LaserScan.h.
| ROS_DEPRECATED uint32_t sensor_msgs::LaserScan_< ContainerAllocator >::get_intensities_size | ( | ) | const [inline] |
Definition at line 88 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::get_intensities_vec | ( | std::vector< float, typename ContainerAllocator::template rebind< float >::other > & | vec | ) | const [inline] |
Definition at line 90 of file LaserScan.h.
| ROS_DEPRECATED uint32_t sensor_msgs::LaserScan_< ContainerAllocator >::get_ranges_size | ( | ) | const [inline] |
Definition at line 84 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::get_ranges_vec | ( | std::vector< float, typename ContainerAllocator::template rebind< float >::other > & | vec | ) | const [inline] |
Definition at line 86 of file LaserScan.h.
| virtual ROS_DEPRECATED uint32_t sensor_msgs::LaserScan_< ContainerAllocator >::serializationLength | ( | ) | const [inline, virtual] |
Definition at line 193 of file LaserScan.h.
| virtual ROS_DEPRECATED uint8_t* sensor_msgs::LaserScan_< ContainerAllocator >::serialize | ( | uint8_t * | write_ptr, | |
| uint32_t | seq | |||
| ) | const [inline, virtual] |
Definition at line 161 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::set_intensities_size | ( | uint32_t | size | ) | [inline] |
Definition at line 89 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::set_intensities_vec | ( | const std::vector< float, typename ContainerAllocator::template rebind< float >::other > & | vec | ) | [inline] |
Definition at line 91 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::set_ranges_size | ( | uint32_t | size | ) | [inline] |
Definition at line 85 of file LaserScan.h.
| ROS_DEPRECATED void sensor_msgs::LaserScan_< ContainerAllocator >::set_ranges_vec | ( | const std::vector< float, typename ContainerAllocator::template rebind< float >::other > & | vec | ) | [inline] |
Definition at line 87 of file LaserScan.h.
| boost::shared_ptr<std::map<std::string, std::string> > sensor_msgs::LaserScan_< ContainerAllocator >::__connection_header |
Definition at line 211 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::angle_increment |
Definition at line 63 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::angle_max |
Definition at line 60 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::angle_min |
Definition at line 57 of file LaserScan.h.
| ::std_msgs::Header_<ContainerAllocator> sensor_msgs::LaserScan_< ContainerAllocator >::header |
Definition at line 54 of file LaserScan.h.
| std::vector<float, typename ContainerAllocator::template rebind<float>::other > sensor_msgs::LaserScan_< ContainerAllocator >::intensities |
Definition at line 81 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::range_max |
Definition at line 75 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::range_min |
Definition at line 72 of file LaserScan.h.
| std::vector<float, typename ContainerAllocator::template rebind<float>::other > sensor_msgs::LaserScan_< ContainerAllocator >::ranges |
Definition at line 78 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::scan_time |
Definition at line 69 of file LaserScan.h.
| float sensor_msgs::LaserScan_< ContainerAllocator >::time_increment |
Definition at line 66 of file LaserScan.h.