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 publishBESTPOS (Oem7RawMessageIf::ConstPtr msg)
 
void publishBESTUTM (Oem7RawMessageIf::ConstPtr msg)
 
void publishBESTVEL (Oem7RawMessageIf::ConstPtr msg)
 
void publishINSVPA (Oem7RawMessageIf::ConstPtr msg)
 
void publishNavSatFix ()
 
void publishOdometry ()
 
void publishROSMessages ()
 
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::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...
 
Oem7RawMessageIf::ConstPtr psrdop2_
 
tf2::Quaternion Z90_DEG_ROTATION
 Rotate ENU to ROS frames. More...
 

Detailed Description

Definition at line 290 of file bestpos_handler.cpp.

Constructor & Destructor Documentation

novatel_oem7_driver::BESTPOSHandler::BESTPOSHandler ( )
inline

Definition at line 662 of file bestpos_handler.cpp.

novatel_oem7_driver::BESTPOSHandler::~BESTPOSHandler ( )
inline

Definition at line 675 of file bestpos_handler.cpp.

Member Function Documentation

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 709 of file bestpos_handler.cpp.

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

Handle a message

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 723 of file bestpos_handler.cpp.

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

Initializes the handler

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 679 of file bestpos_handler.cpp.

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

Definition at line 329 of file bestpos_handler.cpp.

void novatel_oem7_driver::BESTPOSHandler::processPositionAndPublishGPSFix ( )
inlineprivate

Definition at line 393 of file bestpos_handler.cpp.

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

Definition at line 362 of file bestpos_handler.cpp.

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

Definition at line 378 of file bestpos_handler.cpp.

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

Definition at line 371 of file bestpos_handler.cpp.

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

Definition at line 385 of file bestpos_handler.cpp.

void novatel_oem7_driver::BESTPOSHandler::publishNavSatFix ( )
inlineprivate

Definition at line 581 of file bestpos_handler.cpp.

void novatel_oem7_driver::BESTPOSHandler::publishOdometry ( )
inlineprivate

Definition at line 596 of file bestpos_handler.cpp.

void novatel_oem7_driver::BESTPOSHandler::publishROSMessages ( )
inlineprivate

Definition at line 650 of file bestpos_handler.cpp.

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 340 of file bestpos_handler.cpp.

Member Data Documentation

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

Base frame for Odometry.

Definition at line 318 of file bestpos_handler.cpp.

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

Definition at line 301 of file bestpos_handler.cpp.

int32_t novatel_oem7_driver::BESTPOSHandler::bestpos_period_
private

Definition at line 314 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTPOS_pub_
private

Definition at line 292 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTUTM_pub_
private

Definition at line 293 of file bestpos_handler.cpp.

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

Definition at line 302 of file bestpos_handler.cpp.

int32_t novatel_oem7_driver::BESTPOSHandler::bestvel_period_
private

Definition at line 315 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::BESTVEL_pub_
private

Definition at line 294 of file bestpos_handler.cpp.

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

Definition at line 306 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::GPSFix_pub_
private

Definition at line 297 of file bestpos_handler.cpp.

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

Definition at line 303 of file bestpos_handler.cpp.

int32_t novatel_oem7_driver::BESTPOSHandler::inspva_period_
private

Definition at line 316 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::INSPVA_pub_
private

Definition at line 295 of file bestpos_handler.cpp.

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

Definition at line 304 of file bestpos_handler.cpp.

int64_t novatel_oem7_driver::BESTPOSHandler::last_bestpos_
private

Definition at line 310 of file bestpos_handler.cpp.

int64_t novatel_oem7_driver::BESTPOSHandler::last_bestvel_
private

Definition at line 311 of file bestpos_handler.cpp.

int64_t novatel_oem7_driver::BESTPOSHandler::last_inspva_
private

Definition at line 312 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::NavSatFix_pub_
private

Definition at line 298 of file bestpos_handler.cpp.

Oem7RosPublisher novatel_oem7_driver::BESTPOSHandler::Odometry_pub_
private

Definition at line 299 of file bestpos_handler.cpp.

bool novatel_oem7_driver::BESTPOSHandler::position_source_BESTPOS_
private

Definition at line 320 of file bestpos_handler.cpp.

bool novatel_oem7_driver::BESTPOSHandler::position_source_INS_
private

User override: always use INS.

Definition at line 321 of file bestpos_handler.cpp.

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

Definition at line 308 of file bestpos_handler.cpp.

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

Rotate ENU to ROS frames.

Definition at line 323 of file bestpos_handler.cpp.


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


novatel_oem7_driver
Author(s):
autogenerated on Tue Mar 9 2021 03:48:00