Public Member Functions | Private Member Functions | Private Attributes | List of all members
novatel_oem7_driver::BESTPOSHandler Class Reference
Inheritance diagram for novatel_oem7_driver::BESTPOSHandler:
Inheritance graph
[legend]

Public Member Functions

 BESTPOSHandler ()
 
const std::vector< int > & getMessageIds ()
 
void handleMsg (Oem7RawMessageIf::ConstPtr msg)
 
void initialize (ros::NodeHandle &nh)
 
 ~BESTPOSHandler ()
 
- Public Member Functions inherited from novatel_oem7_driver::Oem7MessageHandlerIf
virtual ~Oem7MessageHandlerIf ()
 

Private Member Functions

bool isShortestPeriod (int32_t period)
 
void processPositionAndPublishGPSFix ()
 
void publishBESTGNSSPOS (Oem7RawMessageIf::ConstPtr msg)
 
void publishBESTPOS (Oem7RawMessageIf::ConstPtr msg)
 
void publishBESTUTM (Oem7RawMessageIf::ConstPtr msg)
 
void publishBESTVEL (Oem7RawMessageIf::ConstPtr msg)
 
void publishINSVPA (Oem7RawMessageIf::ConstPtr msg)
 
void publishNavSatFix ()
 
void publishOdometry ()
 
void publishPPPPOS (Oem7RawMessageIf::ConstPtr msg)
 
void publishROSMessages ()
 
void publishTERRASTARINFO (Oem7RawMessageIf::ConstPtr msg)
 
void publishTERRASTARSTATUS (Oem7RawMessageIf::ConstPtr msg)
 
template<typename T >
void updatePeriod (const T &msg, int64_t &last_msg_msec, int32_t &msg_period)
 

Private Attributes

std::string base_frame_
 Base frame for Odometry. More...
 
boost::shared_ptr< novatel_oem7_msgs::BESTGNSSPOS > bestgnsspos_
 
Oem7RosPublisher BESTGNSSPOS_pub_
 
boost::shared_ptr< novatel_oem7_msgs::BESTPOS > bestpos_
 
int32_t bestpos_period_
 
Oem7RosPublisher BESTPOS_pub_
 
Oem7RosPublisher BESTUTM_pub_
 
boost::shared_ptr< novatel_oem7_msgs::BESTVEL > bestvel_
 
int32_t bestvel_period_
 
Oem7RosPublisher BESTVEL_pub_
 
boost::shared_ptr< gps_common::GPSFix > gpsfix_
 
Oem7RosPublisher GPSFix_pub_
 
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
 
int32_t inspva_period_
 
Oem7RosPublisher INSPVA_pub_
 
boost::shared_ptr< novatel_oem7_msgs::INSPVAX > inspvax_
 
int64_t last_bestpos_
 
int64_t last_bestvel_
 
int64_t last_inspva_
 
Oem7RosPublisher NavSatFix_pub_
 
Oem7RosPublisher Odometry_pub_
 
bool position_source_BESTPOS_
 
bool position_source_INS_
 User override: always use INS. More...
 
Oem7RosPublisher PPPPOS_pub_
 
Oem7RawMessageIf::ConstPtr psrdop2_
 
Oem7RosPublisher TERRASTARINFO_pub_
 
Oem7RosPublisher TERRASTARSTATUS_pub_
 
tf2::Quaternion Z90_DEG_ROTATION
 Rotate ENU to ROS frames. More...
 

Detailed Description

Definition at line 358 of file bestpos_handler.cpp.

Constructor & Destructor Documentation

◆ BESTPOSHandler()

novatel_oem7_driver::BESTPOSHandler::BESTPOSHandler ( )
inline

Definition at line 779 of file bestpos_handler.cpp.

◆ ~BESTPOSHandler()

novatel_oem7_driver::BESTPOSHandler::~BESTPOSHandler ( )
inline

Definition at line 792 of file bestpos_handler.cpp.

Member Function Documentation

◆ getMessageIds()

const std::vector<int>& novatel_oem7_driver::BESTPOSHandler::getMessageIds ( )
inlinevirtual
Returns
a vector of Oem7 message IDs to be handled by this Handler.

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 830 of file bestpos_handler.cpp.

◆ handleMsg()

void novatel_oem7_driver::BESTPOSHandler::handleMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlinevirtual

Handle a message

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 848 of file bestpos_handler.cpp.

◆ initialize()

void novatel_oem7_driver::BESTPOSHandler::initialize ( ros::NodeHandle )
inlinevirtual

Initializes the handler

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 796 of file bestpos_handler.cpp.

◆ isShortestPeriod()

bool novatel_oem7_driver::BESTPOSHandler::isShortestPeriod ( int32_t  period)
inlineprivate

Definition at line 402 of file bestpos_handler.cpp.

◆ processPositionAndPublishGPSFix()

void novatel_oem7_driver::BESTPOSHandler::processPositionAndPublishGPSFix ( )
inlineprivate

Definition at line 495 of file bestpos_handler.cpp.

◆ publishBESTGNSSPOS()

void novatel_oem7_driver::BESTPOSHandler::publishBESTGNSSPOS ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 435 of file bestpos_handler.cpp.

◆ publishBESTPOS()

void novatel_oem7_driver::BESTPOSHandler::publishBESTPOS ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 443 of file bestpos_handler.cpp.

◆ publishBESTUTM()

void novatel_oem7_driver::BESTPOSHandler::publishBESTUTM ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 459 of file bestpos_handler.cpp.

◆ publishBESTVEL()

void novatel_oem7_driver::BESTPOSHandler::publishBESTVEL ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 452 of file bestpos_handler.cpp.

◆ publishINSVPA()

void novatel_oem7_driver::BESTPOSHandler::publishINSVPA ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 487 of file bestpos_handler.cpp.

◆ publishNavSatFix()

void novatel_oem7_driver::BESTPOSHandler::publishNavSatFix ( )
inlineprivate

Definition at line 689 of file bestpos_handler.cpp.

◆ publishOdometry()

void novatel_oem7_driver::BESTPOSHandler::publishOdometry ( )
inlineprivate

Definition at line 714 of file bestpos_handler.cpp.

◆ publishPPPPOS()

void novatel_oem7_driver::BESTPOSHandler::publishPPPPOS ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 466 of file bestpos_handler.cpp.

◆ publishROSMessages()

void novatel_oem7_driver::BESTPOSHandler::publishROSMessages ( )
inlineprivate

Definition at line 767 of file bestpos_handler.cpp.

◆ publishTERRASTARINFO()

void novatel_oem7_driver::BESTPOSHandler::publishTERRASTARINFO ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 473 of file bestpos_handler.cpp.

◆ publishTERRASTARSTATUS()

void novatel_oem7_driver::BESTPOSHandler::publishTERRASTARSTATUS ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 480 of file bestpos_handler.cpp.

◆ updatePeriod()

template<typename T >
void novatel_oem7_driver::BESTPOSHandler::updatePeriod ( const T &  msg,
int64_t &  last_msg_msec,
int32_t &  msg_period 
)
inlineprivate

Definition at line 413 of file bestpos_handler.cpp.

Member Data Documentation

◆ base_frame_

std::string novatel_oem7_driver::BESTPOSHandler::base_frame_
private

Base frame for Odometry.

Definition at line 391 of file bestpos_handler.cpp.

◆ bestgnsspos_

boost::shared_ptr<novatel_oem7_msgs::BESTGNSSPOS> novatel_oem7_driver::BESTPOSHandler::bestgnsspos_
private

Definition at line 373 of file bestpos_handler.cpp.

◆ BESTGNSSPOS_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTGNSSPOS_pub_
private

Definition at line 360 of file bestpos_handler.cpp.

◆ bestpos_

boost::shared_ptr<novatel_oem7_msgs::BESTPOS> novatel_oem7_driver::BESTPOSHandler::bestpos_
private

Definition at line 374 of file bestpos_handler.cpp.

◆ bestpos_period_

int32_t novatel_oem7_driver::BESTPOSHandler::bestpos_period_
private

Definition at line 387 of file bestpos_handler.cpp.

◆ BESTPOS_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTPOS_pub_
private

Definition at line 361 of file bestpos_handler.cpp.

◆ BESTUTM_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTUTM_pub_
private

Definition at line 362 of file bestpos_handler.cpp.

◆ bestvel_

boost::shared_ptr<novatel_oem7_msgs::BESTVEL> novatel_oem7_driver::BESTPOSHandler::bestvel_
private

Definition at line 375 of file bestpos_handler.cpp.

◆ bestvel_period_

int32_t novatel_oem7_driver::BESTPOSHandler::bestvel_period_
private

Definition at line 388 of file bestpos_handler.cpp.

◆ BESTVEL_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTVEL_pub_
private

Definition at line 363 of file bestpos_handler.cpp.

◆ gpsfix_

boost::shared_ptr<gps_common::GPSFix> novatel_oem7_driver::BESTPOSHandler::gpsfix_
private

Definition at line 379 of file bestpos_handler.cpp.

◆ GPSFix_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::GPSFix_pub_
private

Definition at line 369 of file bestpos_handler.cpp.

◆ inspva_

boost::shared_ptr<novatel_oem7_msgs::INSPVA> novatel_oem7_driver::BESTPOSHandler::inspva_
private

Definition at line 376 of file bestpos_handler.cpp.

◆ inspva_period_

int32_t novatel_oem7_driver::BESTPOSHandler::inspva_period_
private

Definition at line 389 of file bestpos_handler.cpp.

◆ INSPVA_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::INSPVA_pub_
private

Definition at line 367 of file bestpos_handler.cpp.

◆ inspvax_

boost::shared_ptr<novatel_oem7_msgs::INSPVAX> novatel_oem7_driver::BESTPOSHandler::inspvax_
private

Definition at line 377 of file bestpos_handler.cpp.

◆ last_bestpos_

int64_t novatel_oem7_driver::BESTPOSHandler::last_bestpos_
private

Definition at line 383 of file bestpos_handler.cpp.

◆ last_bestvel_

int64_t novatel_oem7_driver::BESTPOSHandler::last_bestvel_
private

Definition at line 384 of file bestpos_handler.cpp.

◆ last_inspva_

int64_t novatel_oem7_driver::BESTPOSHandler::last_inspva_
private

Definition at line 385 of file bestpos_handler.cpp.

◆ NavSatFix_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::NavSatFix_pub_
private

Definition at line 370 of file bestpos_handler.cpp.

◆ Odometry_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::Odometry_pub_
private

Definition at line 371 of file bestpos_handler.cpp.

◆ position_source_BESTPOS_

bool novatel_oem7_driver::BESTPOSHandler::position_source_BESTPOS_
private

Definition at line 393 of file bestpos_handler.cpp.

◆ position_source_INS_

bool novatel_oem7_driver::BESTPOSHandler::position_source_INS_
private

User override: always use INS.

Definition at line 394 of file bestpos_handler.cpp.

◆ PPPPOS_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::PPPPOS_pub_
private

Definition at line 364 of file bestpos_handler.cpp.

◆ psrdop2_

Oem7RawMessageIf::ConstPtr novatel_oem7_driver::BESTPOSHandler::psrdop2_
private

Definition at line 381 of file bestpos_handler.cpp.

◆ TERRASTARINFO_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::TERRASTARINFO_pub_
private

Definition at line 365 of file bestpos_handler.cpp.

◆ TERRASTARSTATUS_pub_

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::TERRASTARSTATUS_pub_
private

Definition at line 366 of file bestpos_handler.cpp.

◆ Z90_DEG_ROTATION

tf2::Quaternion novatel_oem7_driver::BESTPOSHandler::Z90_DEG_ROTATION
private

Rotate ENU to ROS frames.

Definition at line 396 of file bestpos_handler.cpp.


The documentation for this class was generated from the following file:


novatel_oem7_driver
Author(s):
autogenerated on Sun Mar 19 2023 02:17:37