#include <odom_interface.h>
Public Member Functions | |
| OdomInterface (ros::NodeHandle nh, ros::NodeHandle nh_private) | |
| virtual | ~OdomInterface () | 
Private Types | |
| typedef btMatrix3x3 | MyMatrix | 
| typedef geometry_msgs::PoseStamped | PoseStamped | 
| typedef geometry_msgs::TwistStamped | TwistStamped | 
Private Member Functions | |
| void | heightCallback (const mav_msgs::Height::ConstPtr &height_msg) | 
| void | imuCallback (const sensor_msgs::Imu::ConstPtr &imu_msg) | 
| void | laserPoseCallback (const PoseStamped::ConstPtr &laser_pose_msg) | 
| void | publishPose () | 
Private Attributes | |
| std::string | base_frame_ | 
| std::string | fixed_frame_ | 
| ros::Subscriber | height_subscriber_ | 
| ros::Subscriber | imu_subscriber_ | 
| ros::Subscriber | laser_pose_subscriber_ | 
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | nh_private_ | 
| ros::Publisher | odom_publisher_ | 
| PoseStamped | pose_ | 
| boost::mutex | pose_mutex_ | 
| ros::Publisher | pose_publisher_ | 
| tf::TransformBroadcaster | tf_broadcaster_ | 
Definition at line 18 of file odom_interface.h.
typedef btMatrix3x3 mav::OdomInterface::MyMatrix [private] | 
        
Definition at line 25 of file odom_interface.h.
typedef geometry_msgs::PoseStamped mav::OdomInterface::PoseStamped [private] | 
        
Definition at line 35 of file odom_interface.h.
typedef geometry_msgs::TwistStamped mav::OdomInterface::TwistStamped [private] | 
        
Definition at line 36 of file odom_interface.h.
| mav::OdomInterface::OdomInterface | ( | ros::NodeHandle | nh, | 
| ros::NodeHandle | nh_private | ||
| ) | 
Definition at line 5 of file odom_interface.cpp.
| mav::OdomInterface::~OdomInterface | ( | ) |  [virtual] | 
        
Definition at line 53 of file odom_interface.cpp.
| void mav::OdomInterface::heightCallback | ( | const mav_msgs::Height::ConstPtr & | height_msg | ) |  [private] | 
        
Definition at line 118 of file odom_interface.cpp.
| void mav::OdomInterface::imuCallback | ( | const sensor_msgs::Imu::ConstPtr & | imu_msg | ) |  [private] | 
        
Definition at line 88 of file odom_interface.cpp.
| void mav::OdomInterface::laserPoseCallback | ( | const PoseStamped::ConstPtr & | laser_pose_msg | ) |  [private] | 
        
Definition at line 58 of file odom_interface.cpp.
| void mav::OdomInterface::publishPose | ( | ) |  [private] | 
        
Definition at line 134 of file odom_interface.cpp.
std::string mav::OdomInterface::base_frame_ [private] | 
        
Definition at line 52 of file odom_interface.h.
std::string mav::OdomInterface::fixed_frame_ [private] | 
        
Definition at line 53 of file odom_interface.h.
Definition at line 47 of file odom_interface.h.
Definition at line 46 of file odom_interface.h.
Definition at line 45 of file odom_interface.h.
ros::NodeHandle mav::OdomInterface::nh_ [private] | 
        
Definition at line 40 of file odom_interface.h.
Definition at line 41 of file odom_interface.h.
Definition at line 43 of file odom_interface.h.
PoseStamped mav::OdomInterface::pose_ [private] | 
        
Definition at line 59 of file odom_interface.h.
boost::mutex mav::OdomInterface::pose_mutex_ [private] | 
        
Definition at line 57 of file odom_interface.h.
Definition at line 42 of file odom_interface.h.
Definition at line 48 of file odom_interface.h.