35 #include "novatel_oem7_msgs/SolutionStatus.h" 36 #include "novatel_oem7_msgs/PositionOrVelocityType.h" 37 #include "novatel_oem7_msgs/BESTGNSSPOS.h" 38 #include "novatel_oem7_msgs/BESTPOS.h" 39 #include "novatel_oem7_msgs/BESTUTM.h" 40 #include "novatel_oem7_msgs/BESTVEL.h" 41 #include "novatel_oem7_msgs/PPPPOS.h" 42 #include "novatel_oem7_msgs/AccessStatus.h" 43 #include "novatel_oem7_msgs/GeogatingStatus.h" 44 #include "novatel_oem7_msgs/LocalAreaStatus.h" 45 #include "novatel_oem7_msgs/RegionRestriction.h" 46 #include "novatel_oem7_msgs/SubscriptionPermission.h" 47 #include "novatel_oem7_msgs/SubscriptionType.h" 48 #include "novatel_oem7_msgs/SyncState.h" 49 #include "novatel_oem7_msgs/TERRASTARINFO.h" 50 #include "novatel_oem7_msgs/TERRASTARSTATUS.h" 51 #include "novatel_oem7_msgs/INSPVA.h" 52 #include "novatel_oem7_msgs/INSPVAX.h" 54 #include "nav_msgs/Odometry.h" 55 #include "gps_common/GPSFix.h" 56 #include "sensor_msgs/NavSatFix.h" 57 #include "geometry_msgs/Point.h" 76 return radians * 180.0 / M_PI;
86 return degrees * M_PI / 180.0;
98 std::pow(lat_stdev, 2) +
99 std::pow(lon_stdev, 2) +
100 std::pow(hgt_stdev, 2)
112 return 2.0 * std::sqrt(
113 std::pow(lat_stdev, 2) +
114 std::pow(lon_stdev, 2));
123 return 2.0 * hgt_stdev;
132 return 0.833 * (lat_stdev + lon_stdev + hgt_stdev);
145 switch(bestpos->pos_type.type)
147 case novatel_oem7_msgs::PositionOrVelocityType::PSRDIFF:
148 case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRDIFF:
149 case novatel_oem7_msgs::PositionOrVelocityType::L1_FLOAT:
150 case novatel_oem7_msgs::PositionOrVelocityType::NARROW_FLOAT:
151 case novatel_oem7_msgs::PositionOrVelocityType::L1_INT:
152 case novatel_oem7_msgs::PositionOrVelocityType::WIDE_INT:
153 case novatel_oem7_msgs::PositionOrVelocityType::NARROW_INT:
154 case novatel_oem7_msgs::PositionOrVelocityType::RTK_DIRECT_INS:
155 case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFLOAT:
156 case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFIXED:
157 return gps_common::GPSStatus::STATUS_DGPS_FIX;
159 case novatel_oem7_msgs::PositionOrVelocityType::FIXEDPOS:
160 case novatel_oem7_msgs::PositionOrVelocityType::FIXEDHEIGHT:
161 case novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY:
162 case novatel_oem7_msgs::PositionOrVelocityType::SINGLE:
163 case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRSP:
164 case novatel_oem7_msgs::PositionOrVelocityType::PROPAGATED:
165 case novatel_oem7_msgs::PositionOrVelocityType::OPERATIONAL:
166 case novatel_oem7_msgs::PositionOrVelocityType::WARNING:
167 case novatel_oem7_msgs::PositionOrVelocityType::OUT_OF_BOUNDS:
168 return gps_common::GPSStatus::STATUS_FIX;
170 case novatel_oem7_msgs::PositionOrVelocityType::WAAS:
171 case novatel_oem7_msgs::PositionOrVelocityType::INS_SBAS:
172 case novatel_oem7_msgs::PositionOrVelocityType::PPP_CONVERGING:
173 case novatel_oem7_msgs::PositionOrVelocityType::PPP:
174 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_CONVERGING:
175 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP:
176 case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC_CONVERGING:
177 case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC:
178 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC_CONVERGING:
179 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC:
180 return gps_common::GPSStatus::STATUS_SBAS_FIX;
182 case novatel_oem7_msgs::PositionOrVelocityType::NONE:
183 return gps_common::GPSStatus::STATUS_NO_FIX;
186 ROS_ERROR_STREAM(
"Unknown OEM7 PositionOrVelocityType: " << bestpos->pos_type.type);
187 return gps_common::GPSStatus::STATUS_NO_FIX;
198 static const double SECONDS_IN_GPS_WEEK = 604800.0;
199 static const double MILLISECONDS_IN_SECOND = 1000.0;
201 return gps_week * SECONDS_IN_GPS_WEEK +
202 gps_milliseconds / MILLISECONDS_IN_SECOND;
222 novatel_oem7_msgs::Oem7Header msg_hdr_1,
223 novatel_oem7_msgs::Oem7Header msg_hdr_2)
225 if(msg_hdr_1.gps_week_number > msg_hdr_2.gps_week_number)
228 if(msg_hdr_1.gps_week_number == msg_hdr_2.gps_week_number)
230 if(msg_hdr_1.gps_week_milliseconds > msg_hdr_2.gps_week_milliseconds)
233 if(msg_hdr_1.gps_week_milliseconds == msg_hdr_1.gps_week_milliseconds)
248 switch(covariance_type)
250 case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
251 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
253 case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
254 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
256 case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
257 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
259 case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
260 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
264 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
273 case gps_common::GPSStatus::STATUS_NO_FIX:
274 return sensor_msgs::NavSatStatus::STATUS_NO_FIX;
276 case gps_common::GPSStatus::STATUS_FIX:
277 return sensor_msgs::NavSatStatus::STATUS_FIX;
279 case gps_common::GPSStatus::STATUS_SBAS_FIX:
280 case gps_common::GPSStatus::STATUS_WAAS_FIX:
281 return sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
283 case gps_common::GPSStatus::STATUS_DGPS_FIX:
284 case gps_common::GPSStatus::STATUS_GBAS_FIX:
285 return sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
289 return gps_common::GPSStatus::STATUS_NO_FIX;
297 uint16_t service = 0;
299 if(bestpos->gps_glonass_sig_mask & 0x07)
301 service |= sensor_msgs::NavSatStatus::SERVICE_GPS;
304 if(bestpos->gps_glonass_sig_mask & 0x70)
306 service |= sensor_msgs::NavSatStatus::SERVICE_GLONASS;
309 if(bestpos->galileo_beidou_sig_mask & 0x0F)
311 service |= sensor_msgs::NavSatStatus::SERVICE_GALILEO;
314 if(bestpos->galileo_beidou_sig_mask & 0x70)
316 service |= sensor_msgs::NavSatStatus::SERVICE_COMPASS;
326 geometry_msgs::Point& pt,
342 switch(status.status)
344 case novatel_oem7_msgs::InertialSolutionStatus::INS_HIGH_VARIANCE:
345 case novatel_oem7_msgs::InertialSolutionStatus::INS_SOLUTION_GOOD:
346 case novatel_oem7_msgs::InertialSolutionStatus::INS_SOLUTION_FREE:
347 case novatel_oem7_msgs::InertialSolutionStatus::INS_ALIGNMENT_COMPLETE:
404 return period <= bestpos_period_ &&
405 period <= bestvel_period_ &&
415 int64_t& last_msg_msec,
419 if(last_msg_msec > 0)
421 int32_t period = cur_msg_msec - last_msg_msec;
428 ROS_ERROR_STREAM(
"updatePeriod: msg= " << msg->nov_header.message_id <<
"; per= " << period <<
"; ignored.");
432 last_msg_msec = cur_msg_msec;
440 BESTGNSSPOS_pub_.
publish(bestgnsspos_);
449 BESTPOS_pub_.
publish(bestpos_);
456 BESTVEL_pub_.
publish(bestvel_);
477 TERRASTARINFO_pub_.
publish(terrastarinfo);
484 TERRASTARSTATUS_pub_.
publish(terrastarstatus);
497 gpsfix_.reset(
new gps_common::GPSFix);
499 gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_NONE;
500 gpsfix_->status.orientation_source = gps_common::GPSStatus::SOURCE_NONE;
501 gpsfix_->status.motion_source = gps_common::GPSStatus::SOURCE_NONE;
502 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN;
509 gpsfix_->latitude = bestpos_->lat;
510 gpsfix_->longitude = bestpos_->lon;
511 gpsfix_->altitude = bestpos_->hgt;
514 gpsfix_->position_covariance[0] = std::pow(bestpos_->lon_stdev, 2);
515 gpsfix_->position_covariance[4] = std::pow(bestpos_->lat_stdev, 2);
516 gpsfix_->position_covariance[8] = std::pow(bestpos_->hgt_stdev, 2);
517 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
521 gpsfix_->err =
computeSphericalError( bestpos_->lon_stdev, bestpos_->lat_stdev, bestpos_->hgt_stdev);
524 bestpos_->nov_header.gps_week_number,
525 bestpos_->nov_header.gps_week_milliseconds);
528 gpsfix_->status.satellites_visible = bestpos_->num_svs;
529 gpsfix_->status.satellites_used = bestpos_->num_sol_svs;
532 gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_GPS;
537 gpsfix_->track = bestvel_->trk_gnd;
538 gpsfix_->speed = bestvel_->hor_speed;
539 gpsfix_->climb = bestvel_->ver_speed;
541 if(gpsfix_->time == 0.0)
544 bestvel_->nov_header.gps_week_number,
545 bestvel_->nov_header.gps_week_milliseconds);
548 if(bestvel_->vel_type.type == novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY)
550 gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_DOPPLER;
554 gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_POINTS;
561 gpsfix_->pitch = -inspva_->pitch;
562 gpsfix_->roll = inspva_->roll;
566 gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
567 gpsfix_->status.orientation_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
568 gpsfix_->status.motion_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
572 inspva_->nov_header.gps_week_number,
573 inspva_->nov_header.gps_week_milliseconds);
581 assert(position_source_BESTPOS_ != position_source_INS_ || !position_source_BESTPOS_);
583 if(!position_source_INS_ && !position_source_BESTPOS_)
592 static const float ACCURACY_MARGIN_FACTOR = 1.1;
594 inspvax_->latitude_stdev,
595 inspvax_->longitude_stdev,
596 inspvax_->height_stdev) <
600 bestpos_->hgt_stdev) * ACCURACY_MARGIN_FACTOR;
607 static bool prev_prefer_INS =
false;
608 if(prev_prefer_INS != prefer_INS)
611 <<
" --> " << prefer_INS
613 << inspva_->nov_header.gps_week_number <<
" " 614 << inspva_->nov_header.gps_week_milliseconds <<
"]" 617 prev_prefer_INS = prefer_INS;
620 if(!bestpos_ || prefer_INS)
622 gpsfix_->latitude = inspva_->latitude;
623 gpsfix_->longitude = inspva_->longitude;
627 gpsfix_->altitude = inspva_->height - bestpos_->undulation;
631 gpsfix_->altitude = inspva_->height - inspvax_->undulation;
639 gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
644 gpsfix_->position_covariance[0] = std::pow(inspvax_->longitude_stdev, 2);
645 gpsfix_->position_covariance[4] = std::pow(inspvax_->latitude_stdev, 2);
646 gpsfix_->position_covariance[8] = std::pow(inspvax_->height_stdev, 2);
647 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
651 if(!bestvel_ || prefer_INS)
656 atan2(inspva_->north_velocity, inspva_->east_velocity));
657 if(gpsfix_->track < 0.0)
659 gpsfix_->track + 360.0;
662 gpsfix_->speed = std::sqrt(std::pow(inspva_->north_velocity, 2.0) +
663 std::pow(inspva_->east_velocity, 2.0));
665 gpsfix_->climb = inspva_->up_velocity;
691 if(!gpsfix_ || !bestpos_)
699 navsatfix->latitude = gpsfix_->latitude;
700 navsatfix->longitude = gpsfix_->longitude;
701 navsatfix->altitude = gpsfix_->altitude + bestpos_->undulation;
703 navsatfix->position_covariance[0] = gpsfix_->position_covariance[0];
704 navsatfix->position_covariance[4] = gpsfix_->position_covariance[4];
705 navsatfix->position_covariance[8] = gpsfix_->position_covariance[8];
711 NavSatFix_pub_.
publish(navsatfix);
722 odometry->pose.pose.position,
727 odometry->pose.covariance[ 0] = gpsfix_->position_covariance[0];
728 odometry->pose.covariance[ 7] = gpsfix_->position_covariance[4];
729 odometry->pose.covariance[14] = gpsfix_->position_covariance[8];
746 tf2::Vector3 local_frame_velocity = velocity_transform.
inverse()(tf2::Vector3(inspva_->east_velocity, inspva_->north_velocity, inspva_->up_velocity));
748 odometry->pose.pose.orientation =
tf2::toMsg(ros_orientation);
749 tf2::convert(local_frame_velocity, odometry->twist.twist.linear);
755 odometry->pose.covariance[21] = std::pow(inspvax_->roll_stdev, 2);
756 odometry->pose.covariance[28] = std::pow(inspvax_->pitch_stdev, 2);
757 odometry->pose.covariance[35] = std::pow(inspvax_->azimuth_stdev, 2);
759 odometry->twist.covariance[0] = std::pow(inspvax_->north_velocity_stdev, 2);
760 odometry->twist.covariance[7] = std::pow(inspvax_->east_velocity_stdev, 2);
761 odometry->twist.covariance[14] = std::pow(inspvax_->up_velocity_stdev, 2);
764 Odometry_pub_.
publish(odometry);
783 bestpos_period_(INT_MAX),
784 bestvel_period_(INT_MAX),
785 inspva_period_( INT_MAX),
786 position_source_BESTPOS_(false),
787 position_source_INS_(false)
798 BESTGNSSPOS_pub_.
setup<novatel_oem7_msgs::BESTGNSSPOS>(
"BESTGNSSPOS", nh);
799 BESTPOS_pub_.
setup<novatel_oem7_msgs::BESTPOS>(
"BESTPOS", nh);
800 BESTVEL_pub_.
setup<novatel_oem7_msgs::BESTVEL>(
"BESTVEL", nh);
801 BESTUTM_pub_.
setup<novatel_oem7_msgs::BESTUTM>(
"BESTUTM", nh);
802 PPPPOS_pub_.
setup<novatel_oem7_msgs::PPPPOS>(
"PPPPOS", nh);
803 TERRASTARINFO_pub_.
setup<novatel_oem7_msgs::TERRASTARINFO>(
"TERRASTARINFO", nh);
804 TERRASTARSTATUS_pub_.
setup<novatel_oem7_msgs::TERRASTARSTATUS>(
"TERRASTARSTATUS", nh);
805 INSPVA_pub_.
setup<novatel_oem7_msgs::INSPVA>(
"INSPVA", nh);
806 GPSFix_pub_.
setup<gps_common::GPSFix>(
"GPSFix", nh);
807 NavSatFix_pub_.
setup<sensor_msgs::NavSatFix>(
"NavSatFix", nh);
808 Odometry_pub_.
setup<nav_msgs::Odometry>(
"Odometry", nh);
813 std::string position_source;
814 nh.
getParam(
"position_source", position_source);
815 if(position_source ==
"BESTPOS")
817 position_source_BESTPOS_ =
true;
819 else if(position_source ==
"INSPVAS")
821 position_source_INS_ =
true;
825 position_source =
"BESTPOS or INSPVAS based on quality";
832 static const std::vector<int> MSG_IDS(
850 ROS_DEBUG_STREAM(
"BESTPOS < [id=" << msg->getMessageId() <<
"] periods (BP BV PVA):" <<
851 bestpos_period_ <<
" " <<
852 bestvel_period_ <<
" " <<
912 MakeROSMessage<novatel_oem7_msgs::INSPVAX>(msg,
inspvax_);
double MakeGpsTime_Seconds(uint16_t gps_week, uint32_t gps_milliseconds)
const int PSRDOP2_OEM7_MSGID
const int BESTUTM_OEM7_MSGID
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
double degreesToRadians(double degrees)
Oem7RosPublisher BESTGNSSPOS_pub_
double Get3DPositionError(double lat_stdev, double lon_stdev, double hgt_stdev)
void initialize(ros::NodeHandle &nh)
double radiansToDegrees(double radians)
const int BESTPOS_OEM7_MSGID
ValueRelation GetOem7MessageTimeRelation(novatel_oem7_msgs::Oem7Header msg_hdr_1, novatel_oem7_msgs::Oem7Header msg_hdr_2)
const int BESTVEL_OEM7_MSGID
bool position_source_BESTPOS_
const int TERRASTARSTATUS_OEM7_MSGID
Oem7RawMessageIf::ConstPtr psrdop2_
uint16_t NavSatStatusService(novatel_oem7_msgs::BESTPOS::Ptr bestpos)
bool isShortestPeriod(int32_t period)
void processPositionAndPublishGPSFix()
double computeSphericalError(double lat_stdev, double lon_stdev, double hgt_stdev)
void updatePeriod(const T &msg, int64_t &last_msg_msec, int32_t &msg_period)
double computeVerticalError(double hgt_stdev)
const int INSPVAX_OEM7_MSGID
void publishBESTGNSSPOS(Oem7RawMessageIf::ConstPtr msg)
Oem7RosPublisher TERRASTARSTATUS_pub_
boost::shared_ptr< gps_common::GPSFix > gpsfix_
static void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, char *UTMZone)
Oem7RosPublisher BESTPOS_pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
double computeHorizontalError(double lat_stdev, double lon_stdev)
#define ROS_WARN_THROTTLE(period,...)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > inspvax_
uint8_t GpsStatusToNavSatStatus(int16_t gps_status)
void publishROSMessages()
Oem7RosPublisher INSPVA_pub_
std::string base_frame_
Base frame for Odometry.
Oem7RosPublisher Odometry_pub_
int16_t ToROSGPSStatus(const novatel_oem7_msgs::BESTPOS::Ptr bestpos)
void UTMPointFromGnss(geometry_msgs::Point &pt, double lat, double lon, double hgt)
const int INSPVAS_OEM7_MSGID
void publishTERRASTARINFO(Oem7RawMessageIf::ConstPtr msg)
const std::vector< int > & getMessageIds()
boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > bestgnsspos_
Oem7RosPublisher BESTUTM_pub_
void publish(boost::shared_ptr< M > &msg)
#define ROS_DEBUG_STREAM(args)
Oem7RosPublisher BESTVEL_pub_
Oem7RosPublisher GPSFix_pub_
static int64_t GPSTimeToMsec(uint32_t gps_week_no, uint32_t week_msec)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
bool IsINSSolutionAvailable(const novatel_oem7_msgs::InertialSolutionStatus &status)
void publishTERRASTARSTATUS(Oem7RawMessageIf::ConstPtr msg)
void setup(const std::string &name, ros::NodeHandle &nh)
bool position_source_INS_
User override: always use INS.
#define ROS_INFO_STREAM(args)
Oem7RosPublisher TERRASTARINFO_pub_
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
boost::shared_ptr< novatel_oem7_msgs::BESTVEL > bestvel_
const int BESTGNSSPOS_OEM7_MSGID
void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
void convert(const A &a, B &b)
tf2::Quaternion Z90_DEG_ROTATION
Rotate ENU to ROS frames.
#define ROS_ERROR_STREAM(args)
Oem7RosPublisher PPPPOS_pub_
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
const int PPPPOS_OEM7_MSGID
void GetDOPFromPSRDOP2(const Oem7RawMessageIf::ConstPtr &msg, uint32_t system_to_use, double &gdop, double &pdop, double &hdop, double &vdop, double &tdop)
boost::shared_ptr< novatel_oem7_msgs::BESTPOS > bestpos_
uint8_t GpsFixCovTypeToNavSatFixCovType(uint8_t covariance_type)
void publishPPPPOS(Oem7RawMessageIf::ConstPtr msg)
Oem7RosPublisher NavSatFix_pub_
const int TERRASTARINFO_OEM7_MSGID
void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)