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

Public Member Functions

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

Private Types

typedef std::map< std::string, std::string > imu_config_map_t
 

Private Member Functions

double computeAngularVelocityFromRaw (double raw_gyro)
 
double computeLinearAccelerationFromRaw (double raw_acc)
 
void getImuDescription (oem7_imu_type_t imu_type, std::string &desc)
 
void getImuParam (oem7_imu_type_t imu_type, const std::string &name, std::string &param)
 
int getImuRate (oem7_imu_type_t imu_type)
 
void processInsConfigMsg (Oem7RawMessageIf::ConstPtr msg)
 
void processRawImuMsg (Oem7RawMessageIf::ConstPtr msg)
 
void publishCorrImuMsg (Oem7RawMessageIf::ConstPtr msg)
 
void publishImuMsg ()
 
void publishImuMsg_OEM7 (boost::shared_ptr< sensor_msgs::Imu > &imu)
 
void publishImuMsg_ROS (boost::shared_ptr< sensor_msgs::Imu > &imu)
 
void publishInsPVAXMsg (Oem7RawMessageIf::ConstPtr msg)
 
void publishInsStDevMsg (Oem7RawMessageIf::ConstPtr msg)
 

Private Attributes

boost::shared_ptr< novatel_oem7_msgs::CORRIMU > corrimu_
 
Oem7RosPublisher corrimu_pub_
 
std::string frame_id_
 
imu_config_map_t imu_config_map
 
Oem7RosPublisher imu_pub_
 
imu_rate_t imu_rate_
 IMU output rate. More...
 
double imu_raw_accel_scale_factor_
 IMU-specific raw acceleration scaling. More...
 
double imu_raw_gyro_scale_factor_
 IMU-specific raw gyroscope scaling. More...
 
Oem7RosPublisher insconfig_pub_
 
boost::shared_ptr< novatel_oem7_msgs::INSPVA > inspva_
 
Oem7RosPublisher inspvax_pub_
 
boost::shared_ptr< novatel_oem7_msgs::INSSTDEV > insstdev_
 
Oem7RosPublisher insstdev_pub_
 
ros::NodeHandle nh_
 
bool oem7_imu_reference_frame_
 Backwards compatibility: use OEM7 reference frame, not compliant with REP105. More...
 
Oem7RosPublisher raw_imu_pub_
 

Detailed Description

Definition at line 66 of file ins_handler.cpp.

Member Typedef Documentation

◆ imu_config_map_t

typedef std::map<std::string, std::string> novatel_oem7_driver::INSHandler::imu_config_map_t
private

Definition at line 87 of file ins_handler.cpp.

Constructor & Destructor Documentation

◆ INSHandler()

novatel_oem7_driver::INSHandler::INSHandler ( )
inline

Definition at line 329 of file ins_handler.cpp.

◆ ~INSHandler()

novatel_oem7_driver::INSHandler::~INSHandler ( )
inline

Definition at line 337 of file ins_handler.cpp.

Member Function Documentation

◆ computeAngularVelocityFromRaw()

double novatel_oem7_driver::INSHandler::computeAngularVelocityFromRaw ( double  raw_gyro)
inlineprivate
Returns
angular velocity, rad / sec

Definition at line 278 of file ins_handler.cpp.

◆ computeLinearAccelerationFromRaw()

double novatel_oem7_driver::INSHandler::computeLinearAccelerationFromRaw ( double  raw_acc)
inlineprivate
Returns
linear acceleration, m / sec^2

Definition at line 286 of file ins_handler.cpp.

◆ getImuDescription()

void novatel_oem7_driver::INSHandler::getImuDescription ( oem7_imu_type_t  imu_type,
std::string &  desc 
)
inlineprivate

Definition at line 110 of file ins_handler.cpp.

◆ getImuParam()

void novatel_oem7_driver::INSHandler::getImuParam ( oem7_imu_type_t  imu_type,
const std::string &  name,
std::string &  param 
)
inlineprivate

Definition at line 92 of file ins_handler.cpp.

◆ getImuRate()

int novatel_oem7_driver::INSHandler::getImuRate ( oem7_imu_type_t  imu_type)
inlineprivate

Definition at line 102 of file ins_handler.cpp.

◆ getMessageIds()

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

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 377 of file ins_handler.cpp.

◆ handleMsg()

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

Handle a message

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 393 of file ins_handler.cpp.

◆ initialize()

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

Initializes the handler

Implements novatel_oem7_driver::Oem7MessageHandlerIf.

Definition at line 341 of file ins_handler.cpp.

◆ processInsConfigMsg()

void novatel_oem7_driver::INSHandler::processInsConfigMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 116 of file ins_handler.cpp.

◆ processRawImuMsg()

void novatel_oem7_driver::INSHandler::processRawImuMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 292 of file ins_handler.cpp.

◆ publishCorrImuMsg()

void novatel_oem7_driver::INSHandler::publishCorrImuMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 163 of file ins_handler.cpp.

◆ publishImuMsg()

void novatel_oem7_driver::INSHandler::publishImuMsg ( )
inlineprivate

Definition at line 170 of file ins_handler.cpp.

◆ publishImuMsg_OEM7()

void novatel_oem7_driver::INSHandler::publishImuMsg_OEM7 ( boost::shared_ptr< sensor_msgs::Imu > &  imu)
inlineprivate

Definition at line 198 of file ins_handler.cpp.

◆ publishImuMsg_ROS()

void novatel_oem7_driver::INSHandler::publishImuMsg_ROS ( boost::shared_ptr< sensor_msgs::Imu > &  imu)
inlineprivate

Definition at line 229 of file ins_handler.cpp.

◆ publishInsPVAXMsg()

void novatel_oem7_driver::INSHandler::publishInsPVAXMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 155 of file ins_handler.cpp.

◆ publishInsStDevMsg()

void novatel_oem7_driver::INSHandler::publishInsStDevMsg ( Oem7RawMessageIf::ConstPtr  msg)
inlineprivate

Definition at line 268 of file ins_handler.cpp.

Member Data Documentation

◆ corrimu_

boost::shared_ptr<novatel_oem7_msgs::CORRIMU> novatel_oem7_driver::INSHandler::corrimu_
private

Definition at line 78 of file ins_handler.cpp.

◆ corrimu_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::corrimu_pub_
private

Definition at line 72 of file ins_handler.cpp.

◆ frame_id_

std::string novatel_oem7_driver::INSHandler::frame_id_
private

Definition at line 85 of file ins_handler.cpp.

◆ imu_config_map

imu_config_map_t novatel_oem7_driver::INSHandler::imu_config_map
private

Definition at line 88 of file ins_handler.cpp.

◆ imu_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::imu_pub_
private

Definition at line 70 of file ins_handler.cpp.

◆ imu_rate_

imu_rate_t novatel_oem7_driver::INSHandler::imu_rate_
private

IMU output rate.

Definition at line 81 of file ins_handler.cpp.

◆ imu_raw_accel_scale_factor_

double novatel_oem7_driver::INSHandler::imu_raw_accel_scale_factor_
private

IMU-specific raw acceleration scaling.

Definition at line 83 of file ins_handler.cpp.

◆ imu_raw_gyro_scale_factor_

double novatel_oem7_driver::INSHandler::imu_raw_gyro_scale_factor_
private

IMU-specific raw gyroscope scaling.

Definition at line 82 of file ins_handler.cpp.

◆ insconfig_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::insconfig_pub_
private

Definition at line 75 of file ins_handler.cpp.

◆ inspva_

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

Definition at line 77 of file ins_handler.cpp.

◆ inspvax_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::inspvax_pub_
private

Definition at line 74 of file ins_handler.cpp.

◆ insstdev_

boost::shared_ptr<novatel_oem7_msgs::INSSTDEV> novatel_oem7_driver::INSHandler::insstdev_
private

Definition at line 79 of file ins_handler.cpp.

◆ insstdev_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::insstdev_pub_
private

Definition at line 73 of file ins_handler.cpp.

◆ nh_

ros::NodeHandle novatel_oem7_driver::INSHandler::nh_
private

Definition at line 68 of file ins_handler.cpp.

◆ oem7_imu_reference_frame_

bool novatel_oem7_driver::INSHandler::oem7_imu_reference_frame_
private

Backwards compatibility: use OEM7 reference frame, not compliant with REP105.

Definition at line 90 of file ins_handler.cpp.

◆ raw_imu_pub_

Oem7RosPublisher novatel_oem7_driver::INSHandler::raw_imu_pub_
private

Definition at line 71 of file ins_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