Classes | Functions
gnsstk_ros Namespace Reference

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::SatelliteSystemrosConstellationToGnsstkSatelliteSystem (const std::string &constellation)
 Convert the gnss_info_msgs constellation string to gnsstk constellation enum. More...
 
cras::optional< gnsstk::SatIDsatelliteInfoToSatID (const gnss_info_msgs::SatelliteInfo &info)
 Convert the given satellite info to non-wildcard gnsstk SatID. More...
 

Function Documentation

◆ convert() [1/5]

gnsstk::Position gnsstk_ros::convert ( const geographic_msgs::GeoPoint &  position)

Convert the ROS GeoPoint message to gnsstk Position with Geodetic type.

Parameters
[in]positionThe WGS84 position to convert.
Returns
The corresponding gnsstk position object.

Definition at line 13 of file position.cpp.

◆ convert() [2/5]

gnsstk::Position gnsstk_ros::convert ( const geometry_msgs::Point &  position)

Convert the ROS Point ECEF position to gnsstk Position with Cartesian type.

Parameters
[in]positionThe ECEF position to convert.
Returns
The corresponding gnsstk position object.

Definition at line 29 of file position.cpp.

◆ convert() [3/5]

ros::Time gnsstk_ros::convert ( const gnsstk::CommonTime commonTime)

Convert the given gnsstk time to ROS time.

Parameters
[in]commonTimeThe time to convert.
Returns
The equivalent ROS time.
Exceptions
std::runtime_errorIf the time cannot be represented in ROS.

Definition at line 28 of file time.cpp.

◆ convert() [4/5]

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.

Parameters
[in]xvtThe position and velocity as determined by gnsstk.
[in]satcatIdID of the satellite in the satellite catalog.
[in]posCovPosition covariance to fill on the diagonal.
[in]velCovVelocity covariance to fill on the diagonal.
Returns
The ROS SatellitePosition message corresponding to the given parameter.

Definition at line 45 of file position.cpp.

◆ convert() [5/5]

gnsstk::CommonTime gnsstk_ros::convert ( const ros::Time rosTime)

Covnert the given ROS time to gnsstk time.

Parameters
[in]rosTimeThe ROS time to convert.
Returns
The equivalent gnsstk time.

Definition at line 44 of file time.cpp.

◆ convertToCartesianMsg()

geometry_msgs::Point gnsstk_ros::convertToCartesianMsg ( const gnsstk::Position position)

Convert the given gnsstk Position object to ECEF ROS Point message.

Parameters
[in]positionThe gnsstk position to convert.
Returns
The corresponding ROS Point in ECEF coordinates.

Definition at line 34 of file position.cpp.

◆ convertToGeographicMsg()

geographic_msgs::GeoPoint gnsstk_ros::convertToGeographicMsg ( const gnsstk::Position position)

Convert the given gnsstk Position object to WGS84 ROS GeoPoint message.

Parameters
[in]positionThe gnsstk position to convert.
Returns
The corresponding ROS GeoPoint.

Definition at line 18 of file position.cpp.

◆ getDays()

long gnsstk_ros::getDays ( const gnsstk::CommonTime time)

Get the number of days stored in the given time object.

Parameters
[in]timeThe time to get days of.
Returns
The number of days.

Definition at line 20 of file time.cpp.

◆ getRosConstellationFromPRN()

cras::optional< std::string > gnsstk_ros::getRosConstellationFromPRN ( const std::string &  prn)

Get constellation name from the given PRN string like E03.

Parameters
[in]prnString PRN.
Returns
Constellation name (one of gnss_info_msgs::Enums::CONSTELLATION_* values). If invalid, nullopt.

Definition at line 18 of file constellations.cpp.

◆ getRosConstellationFromSVN()

cras::optional< std::string > gnsstk_ros::getRosConstellationFromSVN ( const std::string &  svn)

Get constellation name from the given SVN string like E203.

Parameters
[in]svnThe SVN of the satellite.
Returns
Constellation name (one of gnss_info_msgs::Enums::CONSTELLATION_* values). If invalid, nullopt.

Definition at line 42 of file constellations.cpp.

◆ gnsstkSatelliteSystemRosConstellation()

cras::optional< std::string > gnsstk_ros::gnsstkSatelliteSystemRosConstellation ( const gnsstk::SatelliteSystem constellation)

Convert the gnsstk constellation enum to gnss_info_msgs constellation string.

Parameters
constellationThe gnsstk constellation enum value.
Returns
The equivalent gnss_info_msgs::Enums::CONSTELLATION_*. Return nullopt if there is no mapping.

Definition at line 113 of file constellations.cpp.

◆ prnIntToString()

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.

Parameters
[in]prnThe numeric PRN.
[in]constellationConstellation name (one of gnss_info_msgs::Enums::CONSTELLATION_* values).
Returns
The PRN string.

Definition at line 72 of file constellations.cpp.

◆ prnStringToInt()

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.

Parameters
[in]prnThe PRN string.
Returns
A pair containing the numeric PRN and constellation name.

Definition at line 48 of file constellations.cpp.

◆ rosConstellationToGnsstkSatelliteSystem()

cras::optional< gnsstk::SatelliteSystem > gnsstk_ros::rosConstellationToGnsstkSatelliteSystem ( const std::string &  constellation)

Convert the gnss_info_msgs constellation string to gnsstk constellation enum.

Parameters
[in]constellationThe constellation string. One of gnss_info_msgs::Enums::CONSTELLATION_*.
Returns
The equivalent gnsstk constellation. Return Unknown if there is no mapping. Return nullopt if constellation is empty.

Definition at line 94 of file constellations.cpp.

◆ satelliteInfoToSatID()

cras::optional< gnsstk::SatID > gnsstk_ros::satelliteInfoToSatID ( const gnss_info_msgs::SatelliteInfo &  info)

Convert the given satellite info to non-wildcard gnsstk SatID.

Parameters
infoInformation about the satellite.
Returns
The SatID object of the given satellite. nullopt if identifying the satellite is not possible.

Definition at line 134 of file constellations.cpp.



gnsstk_ros
Author(s): Martin Pecka
autogenerated on Fri Nov 24 2023 03:50:23