35 #include "novatel_oem7_msgs/SolutionStatus.h" 36 #include "novatel_oem7_msgs/PositionOrVelocityType.h" 37 #include "novatel_oem7_msgs/BESTPOS.h" 38 #include "novatel_oem7_msgs/BESTUTM.h" 39 #include "novatel_oem7_msgs/BESTVEL.h" 40 #include "novatel_oem7_msgs/INSPVA.h" 41 #include "novatel_oem7_msgs/INSPVAX.h" 43 #include "nav_msgs/Odometry.h" 44 #include "gps_common/GPSFix.h" 45 #include "sensor_msgs/NavSatFix.h" 46 #include "geometry_msgs/Point.h" 65 return radians * 180.0 / M_PI;
75 return degrees * M_PI / 180.0;
87 std::pow(lat_stdev, 2) +
88 std::pow(lon_stdev, 2) +
89 std::pow(hgt_stdev, 2)
101 return 2.0 * std::sqrt(
102 std::pow(lat_stdev, 2) +
103 std::pow(lon_stdev, 2));
112 return 2.0 * hgt_stdev;
121 return 0.833 * (lat_stdev + lon_stdev + hgt_stdev);
134 switch(bestpos->pos_type.type)
136 case novatel_oem7_msgs::PositionOrVelocityType::PSRDIFF:
137 case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRDIFF:
138 case novatel_oem7_msgs::PositionOrVelocityType::L1_FLOAT:
139 case novatel_oem7_msgs::PositionOrVelocityType::NARROW_FLOAT:
140 case novatel_oem7_msgs::PositionOrVelocityType::L1_INT:
141 case novatel_oem7_msgs::PositionOrVelocityType::WIDE_INT:
142 case novatel_oem7_msgs::PositionOrVelocityType::NARROW_INT:
143 case novatel_oem7_msgs::PositionOrVelocityType::RTK_DIRECT_INS:
144 case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFLOAT:
145 case novatel_oem7_msgs::PositionOrVelocityType::INS_RTKFIXED:
146 return gps_common::GPSStatus::STATUS_DGPS_FIX;
148 case novatel_oem7_msgs::PositionOrVelocityType::FIXEDPOS:
149 case novatel_oem7_msgs::PositionOrVelocityType::FIXEDHEIGHT:
150 case novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY:
151 case novatel_oem7_msgs::PositionOrVelocityType::SINGLE:
152 case novatel_oem7_msgs::PositionOrVelocityType::INS_PSRSP:
153 case novatel_oem7_msgs::PositionOrVelocityType::PROPAGATED:
154 case novatel_oem7_msgs::PositionOrVelocityType::OPERATIONAL:
155 case novatel_oem7_msgs::PositionOrVelocityType::WARNING:
156 case novatel_oem7_msgs::PositionOrVelocityType::OUT_OF_BOUNDS:
157 return gps_common::GPSStatus::STATUS_FIX;
159 case novatel_oem7_msgs::PositionOrVelocityType::WAAS:
160 case novatel_oem7_msgs::PositionOrVelocityType::INS_SBAS:
161 case novatel_oem7_msgs::PositionOrVelocityType::PPP_CONVERGING:
162 case novatel_oem7_msgs::PositionOrVelocityType::PPP:
163 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_CONVERGING:
164 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP:
165 case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC_CONVERGING:
166 case novatel_oem7_msgs::PositionOrVelocityType::PPP_BASIC:
167 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC_CONVERGING:
168 case novatel_oem7_msgs::PositionOrVelocityType::INS_PPP_BASIC:
169 return gps_common::GPSStatus::STATUS_SBAS_FIX;
171 case novatel_oem7_msgs::PositionOrVelocityType::NONE:
172 return gps_common::GPSStatus::STATUS_NO_FIX;
175 ROS_ERROR_STREAM(
"Unknown OEM7 PositionOrVelocityType: " << bestpos->pos_type.type);
176 return gps_common::GPSStatus::STATUS_NO_FIX;
187 static const double SECONDS_IN_GPS_WEEK = 604800.0;
188 static const double MILLISECONDS_IN_SECOND = 1000.0;
190 return gps_week * SECONDS_IN_GPS_WEEK +
191 gps_milliseconds / MILLISECONDS_IN_SECOND;
211 novatel_oem7_msgs::Oem7Header msg_hdr_1,
212 novatel_oem7_msgs::Oem7Header msg_hdr_2)
214 if(msg_hdr_1.gps_week_number > msg_hdr_2.gps_week_number)
217 if(msg_hdr_1.gps_week_number == msg_hdr_2.gps_week_number)
219 if(msg_hdr_1.gps_week_milliseconds > msg_hdr_2.gps_week_milliseconds)
222 if(msg_hdr_1.gps_week_milliseconds == msg_hdr_1.gps_week_milliseconds)
237 switch(covariance_type)
239 case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
240 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
242 case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
243 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
245 case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
246 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
248 case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
249 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
253 return sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
260 void GpsFixToNavSatFix(
const gps_common::GPSFix::Ptr gpsfix, sensor_msgs::NavSatFix::Ptr navsatfix)
262 navsatfix->latitude = gpsfix->latitude;
263 navsatfix->longitude = gpsfix->longitude;
264 navsatfix->altitude = gpsfix->altitude;
266 navsatfix->position_covariance[0] = gpsfix->position_covariance[0];
267 navsatfix->position_covariance[4] = gpsfix->position_covariance[4];
268 navsatfix->position_covariance[8] = gpsfix->position_covariance[8];
276 geometry_msgs::Point& pt,
331 return period <= bestpos_period_ &&
332 period <= bestvel_period_ &&
342 int64_t& last_msg_msec,
346 if(last_msg_msec > 0)
348 int32_t period = cur_msg_msec - last_msg_msec;
355 ROS_ERROR_STREAM(
"updatePeriod: msg= " << msg->nov_header.message_id <<
"; per= " << period <<
"; ignored.");
359 last_msg_msec = cur_msg_msec;
368 BESTPOS_pub_.
publish(bestpos_);
375 BESTVEL_pub_.
publish(bestvel_);
395 gpsfix_.reset(
new gps_common::GPSFix);
397 gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_NONE;
398 gpsfix_->status.orientation_source = gps_common::GPSStatus::SOURCE_NONE;
399 gpsfix_->status.motion_source = gps_common::GPSStatus::SOURCE_NONE;
400 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN;
407 gpsfix_->latitude = bestpos_->lat;
408 gpsfix_->longitude = bestpos_->lon;
409 gpsfix_->altitude = bestpos_->hgt;
412 gpsfix_->position_covariance[0] = std::pow(bestpos_->lon_stdev, 2);
413 gpsfix_->position_covariance[4] = std::pow(bestpos_->lat_stdev, 2);
414 gpsfix_->position_covariance[8] = std::pow(bestpos_->hgt_stdev, 2);
415 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
419 gpsfix_->err =
computeSphericalError( bestpos_->lon_stdev, bestpos_->lat_stdev, bestpos_->hgt_stdev);
422 bestpos_->nov_header.gps_week_number,
423 bestpos_->nov_header.gps_week_milliseconds);
426 gpsfix_->status.satellites_visible = bestpos_->num_svs;
427 gpsfix_->status.satellites_used = bestpos_->num_sol_svs;
430 gpsfix_->status.position_source = gps_common::GPSStatus::SOURCE_GPS;
435 gpsfix_->track = bestvel_->trk_gnd;
436 gpsfix_->speed = bestvel_->hor_speed;
437 gpsfix_->climb = bestvel_->ver_speed;
439 if(gpsfix_->time == 0.0)
442 bestvel_->nov_header.gps_week_number,
443 bestvel_->nov_header.gps_week_milliseconds);
446 if(bestvel_->vel_type.type == novatel_oem7_msgs::PositionOrVelocityType::DOPPLER_VELOCITY)
448 gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_DOPPLER;
452 gpsfix_->status.motion_source |= gps_common::GPSStatus::SOURCE_POINTS;
458 double undulation = 0;
461 gpsfix_->pitch = -inspva_->pitch;
462 gpsfix_->roll = inspva_->roll;
466 gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
467 gpsfix_->status.orientation_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
468 gpsfix_->status.motion_source = (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
472 inspva_->nov_header.gps_week_number,
473 inspva_->nov_header.gps_week_milliseconds);
481 assert(position_source_BESTPOS_ != position_source_INS_ || !position_source_BESTPOS_);
483 if(!position_source_INS_ && !position_source_BESTPOS_)
485 if(bestpos_ && inspvax_)
490 static const float ACCURACY_MARGIN_FACTOR = 1.1;
492 inspvax_->latitude_stdev,
493 inspvax_->longitude_stdev,
494 inspvax_->height_stdev) <
498 bestpos_->hgt_stdev) * ACCURACY_MARGIN_FACTOR;
505 static bool prev_prefer_INS =
false;
506 if(prev_prefer_INS != prefer_INS)
509 <<
" --> " << prefer_INS
511 << inspva_->nov_header.gps_week_number <<
" " 512 << inspva_->nov_header.gps_week_milliseconds <<
"]" 515 prev_prefer_INS = prefer_INS;
518 if(!bestpos_ || prefer_INS)
520 gpsfix_->latitude = inspva_->latitude;
521 gpsfix_->longitude = inspva_->longitude;
522 gpsfix_->altitude = inspva_->height;
524 gpsfix_->status.position_source |= (gps_common::GPSStatus::SOURCE_GYRO | gps_common::GPSStatus::SOURCE_ACCEL);
528 gpsfix_->altitude = inspva_->height - bestpos_->undulation;
534 gpsfix_->position_covariance[0] = std::pow(inspvax_->longitude_stdev, 2);
535 gpsfix_->position_covariance[4] = std::pow(inspvax_->latitude_stdev, 2);
536 gpsfix_->position_covariance[8] = std::pow(inspvax_->height_stdev, 2);
537 gpsfix_->position_covariance_type = gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
541 gpsfix_->altitude = inspva_->height - inspvax_->undulation;
546 if(!bestvel_ || prefer_INS)
551 atan2(inspva_->north_velocity, inspva_->east_velocity));
552 if(gpsfix_->track < 0.0)
554 gpsfix_->track + 360.0;
557 gpsfix_->speed = std::sqrt(std::pow(inspva_->north_velocity, 2.0) +
558 std::pow(inspva_->east_velocity, 2.0));
560 gpsfix_->climb = inspva_->up_velocity;
593 NavSatFix_pub_.
publish(navsatfix);
604 odometry->pose.pose.position,
609 odometry->pose.covariance[ 0] = gpsfix_->position_covariance[0];
610 odometry->pose.covariance[ 7] = gpsfix_->position_covariance[4];
611 odometry->pose.covariance[14] = gpsfix_->position_covariance[8];
619 odometry->twist.twist.linear.x = inspva_->north_velocity;
620 odometry->twist.twist.linear.y = inspva_->east_velocity;
621 odometry->twist.twist.linear.z = inspva_->up_velocity;
632 odometry->pose.pose.orientation =
tf2::toMsg(ros_orientation);
638 odometry->pose.covariance[21] = std::pow(inspvax_->roll_stdev, 2);
639 odometry->pose.covariance[28] = std::pow(inspvax_->pitch_stdev, 2);
640 odometry->pose.covariance[35] = std::pow(inspvax_->azimuth_stdev, 2);
642 odometry->twist.covariance[0] = std::pow(inspvax_->north_velocity_stdev, 2);
643 odometry->twist.covariance[7] = std::pow(inspvax_->east_velocity_stdev, 2);
644 odometry->twist.covariance[14] = std::pow(inspvax_->up_velocity_stdev, 2);
647 Odometry_pub_.
publish(odometry);
666 bestpos_period_(INT_MAX),
667 bestvel_period_(INT_MAX),
668 inspva_period_( INT_MAX),
669 position_source_BESTPOS_(false),
670 position_source_INS_(false)
681 BESTPOS_pub_.
setup<novatel_oem7_msgs::BESTPOS>(
"BESTPOS", nh);
682 BESTVEL_pub_.
setup<novatel_oem7_msgs::BESTVEL>(
"BESTVEL", nh);
683 BESTUTM_pub_.
setup<novatel_oem7_msgs::BESTUTM>(
"BESTUTM", nh);
684 INSPVA_pub_.
setup<novatel_oem7_msgs::INSPVA>(
"INSPVA", nh);
685 GPSFix_pub_.
setup<gps_common::GPSFix>(
"GPSFix", nh);
686 NavSatFix_pub_.
setup<sensor_msgs::NavSatFix>(
"NavSatFix", nh);
687 Odometry_pub_.
setup<nav_msgs::Odometry>(
"Odometry", nh);
692 std::string position_source;
693 nh.
getParam(
"position_source", position_source);
694 if(position_source ==
"BESTPOS")
696 position_source_BESTPOS_ =
true;
698 else if(position_source ==
"INSPVAS")
700 position_source_INS_ =
true;
704 position_source =
"BESTPOS or INSPVAS based on quality";
711 static const std::vector<int> MSG_IDS(
725 ROS_DEBUG_STREAM(
"BESTPOS < [id=" << msg->getMessageId() <<
"] periods (BP BV PVA):" <<
726 bestpos_period_ <<
" " <<
727 bestvel_period_ <<
" " <<
772 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)
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_
Oem7RawMessageIf::ConstPtr psrdop2_
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
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_
void publishBESTPOS(Oem7RawMessageIf::ConstPtr msg)
double computeHorizontalError(double lat_stdev, double lon_stdev)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > inspvax_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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
const std::vector< int > & getMessageIds()
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)
void setup(const std::string &name, ros::NodeHandle &nh)
bool position_source_INS_
User override: always use INS.
#define ROS_INFO_STREAM(args)
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)
bool getParam(const std::string &key, std::string &s) const
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_
void publishBESTUTM(Oem7RawMessageIf::ConstPtr msg)
void publishINSVPA(Oem7RawMessageIf::ConstPtr msg)
void GpsFixToNavSatFix(const gps_common::GPSFix::Ptr gpsfix, sensor_msgs::NavSatFix::Ptr navsatfix)
tf2::Quaternion Z90_DEG_ROTATION
Rotate ENU to ROS frames.
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
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)
Oem7RosPublisher NavSatFix_pub_
void publishBESTVEL(Oem7RawMessageIf::ConstPtr msg)