Classes | |
struct | UnixEpoch |
UNIX epoch (1 Jan 1970) represented in gnsstk CommonTime means. Static values for efficient computations. More... | |
Functions | |
gnsstk::Position | convert (const geographic_msgs::GeoPoint &position) |
Convert the ROS GeoPoint message to gnsstk Position with Geodetic type. More... | |
gnsstk::Position | convert (const geometry_msgs::Point &position) |
Convert the ROS Point ECEF position to gnsstk Position with Cartesian type. More... | |
ros::Time | convert (const gnsstk::CommonTime &commonTime) |
Convert the given gnsstk time to ROS time. More... | |
gnss_info_msgs::SatellitePosition | convert (const gnsstk::Xvt &xvt, uint32_t satcatId, double posCov, double velCov) |
Convert the given position and velocity to ROS SatellitePosition message. More... | |
gnsstk::CommonTime | convert (const ros::Time &rosTime) |
Covnert the given ROS time to gnsstk time. More... | |
geometry_msgs::Point | convertToCartesianMsg (const gnsstk::Position &position) |
Convert the given gnsstk Position object to ECEF ROS Point message. More... | |
geographic_msgs::GeoPoint | convertToGeographicMsg (const gnsstk::Position &position) |
Convert the given gnsstk Position object to WGS84 ROS GeoPoint message. More... | |
long | getDays (const gnsstk::CommonTime &time) |
Get the number of days stored in the given time object. More... | |
cras::optional< std::string > | getRosConstellationFromPRN (const std::string &prn) |
Get constellation name from the given PRN string like E03. More... | |
cras::optional< std::string > | getRosConstellationFromSVN (const std::string &svn) |
Get constellation name from the given SVN string like E203. More... | |
cras::optional< std::string > | gnsstkSatelliteSystemRosConstellation (const gnsstk::SatelliteSystem &constellation) |
Convert the gnsstk constellation enum to gnss_info_msgs constellation string. More... | |
cras::optional< std::string > | prnIntToString (int32_t prn, const std::string &constellation) |
Convert the given numeric PRN and constellation to string PRN like E03. More... | |
cras::optional< std::pair< int32_t, std::string > > | prnStringToInt (const std::string &prn) |
Convert the given PRN string like E03 to integer like 3 and constellation name. More... | |
cras::optional< gnsstk::SatelliteSystem > | rosConstellationToGnsstkSatelliteSystem (const std::string &constellation) |
Convert the gnss_info_msgs constellation string to gnsstk constellation enum. More... | |
cras::optional< gnsstk::SatID > | satelliteInfoToSatID (const gnss_info_msgs::SatelliteInfo &info) |
Convert the given satellite info to non-wildcard gnsstk SatID. More... | |
gnsstk::Position gnsstk_ros::convert | ( | const geographic_msgs::GeoPoint & | position | ) |
Convert the ROS GeoPoint message to gnsstk Position with Geodetic type.
[in] | position | The WGS84 position to convert. |
Definition at line 13 of file position.cpp.
gnsstk::Position gnsstk_ros::convert | ( | const geometry_msgs::Point & | position | ) |
Convert the ROS Point ECEF position to gnsstk Position with Cartesian type.
[in] | position | The ECEF position to convert. |
Definition at line 29 of file position.cpp.
ros::Time gnsstk_ros::convert | ( | const gnsstk::CommonTime & | commonTime | ) |
gnss_info_msgs::SatellitePosition gnsstk_ros::convert | ( | const gnsstk::Xvt & | xvt, |
uint32_t | satcatId, | ||
double | posCov, | ||
double | velCov | ||
) |
Convert the given position and velocity to ROS SatellitePosition message.
[in] | xvt | The position and velocity as determined by gnsstk. |
[in] | satcatId | ID of the satellite in the satellite catalog. |
[in] | posCov | Position covariance to fill on the diagonal. |
[in] | velCov | Velocity covariance to fill on the diagonal. |
Definition at line 45 of file position.cpp.
gnsstk::CommonTime gnsstk_ros::convert | ( | const ros::Time & | rosTime | ) |
geometry_msgs::Point gnsstk_ros::convertToCartesianMsg | ( | const gnsstk::Position & | position | ) |
Convert the given gnsstk Position object to ECEF ROS Point message.
[in] | position | The gnsstk position to convert. |
Definition at line 34 of file position.cpp.
geographic_msgs::GeoPoint gnsstk_ros::convertToGeographicMsg | ( | const gnsstk::Position & | position | ) |
Convert the given gnsstk Position object to WGS84 ROS GeoPoint message.
[in] | position | The gnsstk position to convert. |
Definition at line 18 of file position.cpp.
long gnsstk_ros::getDays | ( | const gnsstk::CommonTime & | time | ) |
cras::optional< std::string > gnsstk_ros::getRosConstellationFromPRN | ( | const std::string & | prn | ) |
Get constellation name from the given PRN string like E03.
[in] | prn | String PRN. |
gnss_info_msgs::Enums::CONSTELLATION_*
values). If invalid, nullopt. Definition at line 18 of file constellations.cpp.
cras::optional< std::string > gnsstk_ros::getRosConstellationFromSVN | ( | const std::string & | svn | ) |
Get constellation name from the given SVN string like E203.
[in] | svn | The SVN of the satellite. |
gnss_info_msgs::Enums::CONSTELLATION_*
values). If invalid, nullopt. Definition at line 42 of file constellations.cpp.
cras::optional< std::string > gnsstk_ros::gnsstkSatelliteSystemRosConstellation | ( | const gnsstk::SatelliteSystem & | constellation | ) |
Convert the gnsstk constellation enum to gnss_info_msgs constellation string.
constellation | The gnsstk constellation enum value. |
gnss_info_msgs::Enums::CONSTELLATION_*
. Return nullopt
if there is no mapping. Definition at line 113 of file constellations.cpp.
cras::optional< std::string > gnsstk_ros::prnIntToString | ( | int32_t | prn, |
const std::string & | constellation | ||
) |
Convert the given numeric PRN and constellation to string PRN like E03.
[in] | prn | The numeric PRN. |
[in] | constellation | Constellation name (one of gnss_info_msgs::Enums::CONSTELLATION_* values). |
Definition at line 72 of file constellations.cpp.
cras::optional< std::pair< int32_t, std::string > > gnsstk_ros::prnStringToInt | ( | const std::string & | prn | ) |
Convert the given PRN string like E03 to integer like 3 and constellation name.
[in] | prn | The PRN string. |
Definition at line 48 of file constellations.cpp.
cras::optional< gnsstk::SatelliteSystem > gnsstk_ros::rosConstellationToGnsstkSatelliteSystem | ( | const std::string & | constellation | ) |
Convert the gnss_info_msgs constellation string to gnsstk constellation enum.
[in] | constellation | The constellation string. One of gnss_info_msgs::Enums::CONSTELLATION_* . |
Unknown
if there is no mapping. Return nullopt
if constellation
is empty. Definition at line 94 of file constellations.cpp.
cras::optional< gnsstk::SatID > gnsstk_ros::satelliteInfoToSatID | ( | const gnss_info_msgs::SatelliteInfo & | info | ) |
Convert the given satellite info to non-wildcard gnsstk SatID.
info | Information about the satellite. |
nullopt
if identifying the satellite is not possible. Definition at line 134 of file constellations.cpp.