#include <GPSFix.h>
Public Types | |
enum | { COVARIANCE_TYPE_UNKNOWN = 0 } |
enum | { COVARIANCE_TYPE_APPROXIMATED = 1 } |
enum | { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 } |
enum | { COVARIANCE_TYPE_KNOWN = 3 } |
typedef double | _altitude_type |
typedef double | _climb_type |
typedef double | _dip_type |
typedef double | _err_climb_type |
typedef double | _err_dip_type |
typedef double | _err_horz_type |
typedef double | _err_pitch_type |
typedef double | _err_roll_type |
typedef double | _err_speed_type |
typedef double | _err_time_type |
typedef double | _err_track_type |
typedef double | _err_type |
typedef double | _err_vert_type |
typedef double | _gdop_type |
typedef double | _hdop_type |
typedef ::std_msgs::Header_ < ContainerAllocator > | _header_type |
typedef double | _latitude_type |
typedef double | _longitude_type |
typedef double | _pdop_type |
typedef double | _pitch_type |
typedef boost::array< double, 9 > | _position_covariance_type |
typedef uint8_t | _position_covariance_type_type |
typedef double | _roll_type |
typedef double | _speed_type |
typedef ::clearpath_sensors::GPSStatus_ < ContainerAllocator > | _status_type |
typedef double | _tdop_type |
typedef double | _time_type |
typedef double | _track_type |
typedef double | _vdop_type |
typedef boost::shared_ptr < ::clearpath_sensors::GPSFix_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::clearpath_sensors::GPSFix_ < ContainerAllocator > > | Ptr |
typedef GPSFix_ < 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_position_covariance_size () const |
GPSFix_ (const ContainerAllocator &_alloc) | |
GPSFix_ () | |
virtual ROS_DEPRECATED uint32_t | serializationLength () const |
virtual ROS_DEPRECATED uint8_t * | serialize (uint8_t *write_ptr, uint32_t seq) const |
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 | |
double | altitude |
double | climb |
double | dip |
double | err |
double | err_climb |
double | err_dip |
double | err_horz |
double | err_pitch |
double | err_roll |
double | err_speed |
double | err_time |
double | err_track |
double | err_vert |
double | gdop |
double | hdop |
::std_msgs::Header_ < ContainerAllocator > | header |
double | latitude |
double | longitude |
double | pdop |
double | pitch |
boost::array< double, 9 > | position_covariance |
uint8_t | position_covariance_type |
double | roll |
double | speed |
::clearpath_sensors::GPSStatus_ < ContainerAllocator > | status |
double | tdop |
double | time |
double | track |
double | vdop |
Static Private Member Functions | |
static const char * | __s_getDataType_ () |
static const char * | __s_getMD5Sum_ () |
static const char * | __s_getMessageDefinition_ () |
Definition at line 17 of file GPSFix.h.
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_altitude_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_climb_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_dip_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_climb_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_dip_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_horz_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_pitch_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_roll_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_speed_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_time_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_track_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_err_vert_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_gdop_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_hdop_type |
typedef ::std_msgs::Header_<ContainerAllocator> clearpath_sensors::GPSFix_< ContainerAllocator >::_header_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_latitude_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_longitude_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_pdop_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_pitch_type |
typedef boost::array<double, 9> clearpath_sensors::GPSFix_< ContainerAllocator >::_position_covariance_type |
typedef uint8_t clearpath_sensors::GPSFix_< ContainerAllocator >::_position_covariance_type_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_roll_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_speed_type |
typedef ::clearpath_sensors::GPSStatus_<ContainerAllocator> clearpath_sensors::GPSFix_< ContainerAllocator >::_status_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_tdop_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_time_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_track_type |
typedef double clearpath_sensors::GPSFix_< ContainerAllocator >::_vdop_type |
typedef boost::shared_ptr< ::clearpath_sensors::GPSFix_<ContainerAllocator> const> clearpath_sensors::GPSFix_< ContainerAllocator >::ConstPtr |
typedef boost::shared_ptr< ::clearpath_sensors::GPSFix_<ContainerAllocator> > clearpath_sensors::GPSFix_< ContainerAllocator >::Ptr |
typedef GPSFix_<ContainerAllocator> clearpath_sensors::GPSFix_< ContainerAllocator >::Type |
anonymous enum |
anonymous enum |
anonymous enum |
anonymous enum |
clearpath_sensors::GPSFix_< ContainerAllocator >::GPSFix_ | ( | ) | [inline] |
clearpath_sensors::GPSFix_< ContainerAllocator >::GPSFix_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__getDataType | ( | ) | const [inline] |
ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__getMD5Sum | ( | ) | const [inline] |
ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__getMessageDefinition | ( | ) | const [inline] |
static ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getDataType | ( | ) | [inline, static] |
static const char* clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getDataType_ | ( | ) | [inline, static, private] |
static ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getMD5Sum | ( | ) | [inline, static] |
static const char* clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getMD5Sum_ | ( | ) | [inline, static, private] |
static ROS_DEPRECATED const std::string clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getMessageDefinition | ( | ) | [inline, static] |
static const char* clearpath_sensors::GPSFix_< ContainerAllocator >::__s_getMessageDefinition_ | ( | ) | [inline, static, private] |
virtual ROS_DEPRECATED uint8_t* clearpath_sensors::GPSFix_< ContainerAllocator >::deserialize | ( | uint8_t * | read_ptr | ) | [inline, virtual] |
ROS_DEPRECATED uint32_t clearpath_sensors::GPSFix_< ContainerAllocator >::get_position_covariance_size | ( | ) | const [inline] |
virtual ROS_DEPRECATED uint32_t clearpath_sensors::GPSFix_< ContainerAllocator >::serializationLength | ( | ) | const [inline, virtual] |
virtual ROS_DEPRECATED uint8_t* clearpath_sensors::GPSFix_< ContainerAllocator >::serialize | ( | uint8_t * | write_ptr, | |
uint32_t | seq | |||
) | const [inline, virtual] |
double clearpath_sensors::GPSFix_< ContainerAllocator >::altitude |
double clearpath_sensors::GPSFix_< ContainerAllocator >::climb |
double clearpath_sensors::GPSFix_< ContainerAllocator >::dip |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_climb |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_dip |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_horz |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_pitch |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_roll |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_speed |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_time |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_track |
double clearpath_sensors::GPSFix_< ContainerAllocator >::err_vert |
double clearpath_sensors::GPSFix_< ContainerAllocator >::gdop |
double clearpath_sensors::GPSFix_< ContainerAllocator >::hdop |
::std_msgs::Header_<ContainerAllocator> clearpath_sensors::GPSFix_< ContainerAllocator >::header |
double clearpath_sensors::GPSFix_< ContainerAllocator >::latitude |
double clearpath_sensors::GPSFix_< ContainerAllocator >::longitude |
double clearpath_sensors::GPSFix_< ContainerAllocator >::pdop |
double clearpath_sensors::GPSFix_< ContainerAllocator >::pitch |
boost::array<double, 9> clearpath_sensors::GPSFix_< ContainerAllocator >::position_covariance |
uint8_t clearpath_sensors::GPSFix_< ContainerAllocator >::position_covariance_type |
double clearpath_sensors::GPSFix_< ContainerAllocator >::roll |
double clearpath_sensors::GPSFix_< ContainerAllocator >::speed |
::clearpath_sensors::GPSStatus_<ContainerAllocator> clearpath_sensors::GPSFix_< ContainerAllocator >::status |
double clearpath_sensors::GPSFix_< ContainerAllocator >::tdop |
double clearpath_sensors::GPSFix_< ContainerAllocator >::time |
double clearpath_sensors::GPSFix_< ContainerAllocator >::track |
double clearpath_sensors::GPSFix_< ContainerAllocator >::vdop |