#include <ekf_interface.h>
Public Member Functions | |
EKFInterface (ros::NodeHandle &nh, CommPtr &comm) | |
Private Member Functions | |
void | processEkfData (uint8_t *buf, uint32_t bufLength) |
void | stateCallback (const sensor_fusion_comm::ExtEkfConstPtr &msg) |
Private Attributes | |
CommPtr | comm_ |
HLI_EKF_STATE | ekf_state_msg_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | pnh_ |
ros::Publisher | state_pub_ |
ros::Subscriber | state_sub_ |
Definition at line 40 of file ekf_interface.h.
EKFInterface::EKFInterface | ( | ros::NodeHandle & | nh, |
CommPtr & | comm | ||
) |
Definition at line 36 of file ekf_interface.cpp.
void EKFInterface::processEkfData | ( | uint8_t * | buf, |
uint32_t | bufLength | ||
) | [private] |
Definition at line 45 of file ekf_interface.cpp.
void EKFInterface::stateCallback | ( | const sensor_fusion_comm::ExtEkfConstPtr & | msg | ) | [private] |
Definition at line 79 of file ekf_interface.cpp.
CommPtr EKFInterface::comm_ [private] |
Definition at line 45 of file ekf_interface.h.
HLI_EKF_STATE EKFInterface::ekf_state_msg_ [private] |
Definition at line 50 of file ekf_interface.h.
ros::NodeHandle EKFInterface::nh_ [private] |
Definition at line 43 of file ekf_interface.h.
ros::NodeHandle EKFInterface::pnh_ [private] |
Definition at line 44 of file ekf_interface.h.
ros::Publisher EKFInterface::state_pub_ [private] |
Definition at line 47 of file ekf_interface.h.
ros::Subscriber EKFInterface::state_sub_ [private] |
Definition at line 48 of file ekf_interface.h.