Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes
imu_filter::TfHandler Class Reference

#include <tf_handler.h>

List of all members.

Public Member Functions

void broadcastIMUFrame (const Eigen::Quaterniond &orientation, const Eigen::Vector3d &position, const ros::Time &time)
 broadcast a frame named imu_local
void broadcastTfPose (const Eigen::Affine3d &pose, const ros::Time &t, const std::string &frame)
 function to broadcast a specific tf frame with a given pose
void publishImuState (const ImuState &state, const ros::Time &t)
 function to broadcast a messages reflecting the current state estimate of the IMU
void publishKFRelativePose (const Eigen::Affine3d &pose, const ros::Time &t)
 publish a pose message for the keyframe relative pose estimate
void setBaseFrame (const std::string &frame_id)
 set the name of the tf base frame
void setPseudoObservation (const Observation::Vector &vec, const ros::Time &time)
 broadcast a pseude observation frame

Static Public Member Functions

static TfHandlerinstance ()
 get the singleton instance

Private Member Functions

 TfHandler ()
 TfHandler (const TfHandler &)

Private Attributes

std::string baseFrame_
tf::TransformBroadcaster bc_
tf::Transform imuFrame_
ros::NodeHandle nh_
geometry_msgs::PoseStamped poseMsg_
ros::Publisher pubGravity_
ros::Publisher pubGtPos_
ros::Publisher pubGtRot_
ros::Publisher pubImuABias_
ros::Publisher pubImuGBias_
ros::Publisher pubImuPos_
ros::Publisher pubImuPose_
ros::Publisher pubImuRot_
ros::Publisher pubImuVel_
ros::Publisher pubPoseRelativeToKf_
ros::Publisher pubPseudoPos_
ros::Publisher pubPseudoRot_
geometry_msgs::Quaternion qMsg_
tf::TransformListener tfIn_
tf::StampedTransform tmpT_
geometry_msgs::Vector3 vMsg_

Detailed Description

Definition at line 51 of file tf_handler.h.


Constructor & Destructor Documentation

imu_filter::TfHandler::TfHandler ( ) [inline, private]

Definition at line 181 of file tf_handler.h.


Member Function Documentation

void imu_filter::TfHandler::broadcastIMUFrame ( const Eigen::Quaterniond &  orientation,
const Eigen::Vector3d &  position,
const ros::Time time 
) [inline]

broadcast a frame named imu_local

Parameters:
orientationthe frame orientation
positionthe frame position
timetransform time

Definition at line 69 of file tf_handler.h.

void imu_filter::TfHandler::broadcastTfPose ( const Eigen::Affine3d &  pose,
const ros::Time t,
const std::string &  frame 
) [inline]

function to broadcast a specific tf frame with a given pose

Parameters:
posethe pose of the frame relative to the base frame
tthe transform time
framethe name of the frame

Definition at line 103 of file tf_handler.h.

static TfHandler& imu_filter::TfHandler::instance ( ) [inline, static]

get the singleton instance

Definition at line 57 of file tf_handler.h.

void imu_filter::TfHandler::publishImuState ( const ImuState state,
const ros::Time t 
) [inline]

function to broadcast a messages reflecting the current state estimate of the IMU

This function published messages describing the state:

  • Pose message for the current IMU pose
  • Quaternion message for the orientation
  • Vec3 message for the position
  • Vec3 message for the velocity
  • Vec3 message for the gyro bias
  • Vec3 message for the accelerometer bias
  • Vec3 message for the gravity vector
Parameters:
statethe IMU state
tthe transform time

Definition at line 125 of file tf_handler.h.

void imu_filter::TfHandler::publishKFRelativePose ( const Eigen::Affine3d &  pose,
const ros::Time t 
) [inline]

publish a pose message for the keyframe relative pose estimate

Definition at line 170 of file tf_handler.h.

void imu_filter::TfHandler::setBaseFrame ( const std::string &  frame_id) [inline]

set the name of the tf base frame

Definition at line 165 of file tf_handler.h.

void imu_filter::TfHandler::setPseudoObservation ( const Observation::Vector vec,
const ros::Time time 
) [inline]

broadcast a pseude observation frame

Parameters:
vecthe observation which will be conerted into a pose
timethe transform time

Definition at line 81 of file tf_handler.h.


Member Data Documentation

std::string imu_filter::TfHandler::baseFrame_ [private]

Definition at line 201 of file tf_handler.h.

Definition at line 202 of file tf_handler.h.

Definition at line 204 of file tf_handler.h.

Definition at line 179 of file tf_handler.h.

geometry_msgs::PoseStamped imu_filter::TfHandler::poseMsg_ [private]

Definition at line 222 of file tf_handler.h.

Definition at line 217 of file tf_handler.h.

Definition at line 210 of file tf_handler.h.

Definition at line 209 of file tf_handler.h.

Definition at line 216 of file tf_handler.h.

Definition at line 215 of file tf_handler.h.

Definition at line 213 of file tf_handler.h.

Definition at line 211 of file tf_handler.h.

Definition at line 212 of file tf_handler.h.

Definition at line 214 of file tf_handler.h.

Definition at line 218 of file tf_handler.h.

Definition at line 208 of file tf_handler.h.

Definition at line 207 of file tf_handler.h.

geometry_msgs::Quaternion imu_filter::TfHandler::qMsg_ [private]

Definition at line 220 of file tf_handler.h.

Definition at line 203 of file tf_handler.h.

Definition at line 205 of file tf_handler.h.

geometry_msgs::Vector3 imu_filter::TfHandler::vMsg_ [private]

Definition at line 221 of file tf_handler.h.


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


imu_filter
Author(s): Sebastian Klose
autogenerated on Thu Dec 12 2013 11:24:43