Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
System Class Reference

#include <System.h>

List of all members.

Public Member Functions

void Run ()
 System ()

Private Types

typedef std::queue
< sensor_msgs::Imu > 
ImuQueue
typedef std::queue
< geometry_msgs::PoseWithCovarianceStamped > 
PoseQueue

Private Member Functions

template<class T >
bool findClosest (const ros::Time &timestamp, std::queue< T > &queue, T *obj, const double &max_delay=0.01)
 finds object in queue with timestamp closest to timestamp. Requires that T has a std_msgs::header field named "header"
void imageCallback (const sensor_msgs::ImageConstPtr &img)
void imuCallback (const sensor_msgs::ImuConstPtr &msg)
void init (const CVD::ImageRef &size)
void keyboardCallback (const std_msgs::StringConstPtr &kb_input)
bool keyframesservice (ptam_com::KeyFrame_srvRequest &req, ptam_com::KeyFrame_srvResponse &resp)
bool pointcloudservice (ptam_com::PointCloudRequest &req, ptam_com::PointCloudResponse &resp)
void publishPoseAndInfo (const std_msgs::Header &header)
void publishPreviewImage (CVD::Image< CVD::byte > &img, const std_msgs::Header &header)
void quaternionToRotationMatrix (const geometry_msgs::Quaternion &q, TooN::SO3< double > &R)
bool transformPoint (const std::string &target_frame, const std_msgs::Header &header, const geometry_msgs::Point &t_in, TooN::Vector< 3 > &t_out)
bool transformQuaternion (const std::string &target_frame, const std_msgs::Header &header, const geometry_msgs::Quaternion &q_in, TooN::SO3< double > &r_out)

Static Private Member Functions

static void GUICommandCallBack (void *ptr, std::string sCommand, std::string sParams)

Private Attributes

bool first_frame_
ros::NodeHandle image_nh_
ros::CallbackQueue image_queue_
CVD::Image< CVD::byte > img_bw_
CVD::Image< CVD::Rgb< CVD::byte > > img_rgb_
ImuQueue imu_msgs_
GLWindow2mGLWindow
ATANCamerampCamera
MapmpMap
MapMakermpMapMaker
MapViewermpMapViewer
TrackermpTracker
ros::NodeHandle nh_
ros::Publisher pub_info_
ros::Publisher pub_pose_
ros::Publisher pub_pose_world_
image_transport::Publisher pub_preview_image_
ros::ServiceServer srvKF_
ros::ServiceServer srvPC_
ros::Subscriber sub_calibration_
image_transport::Subscriber sub_image_
ros::Subscriber sub_imu_
ros::Subscriber sub_kb_input_
tf::TransformBroadcaster tf_pub_
tf::TransformListener tf_sub_

Detailed Description

Definition at line 46 of file System.h.


Member Typedef Documentation

typedef std::queue<sensor_msgs::Imu> System::ImuQueue [private]

Definition at line 48 of file System.h.

typedef std::queue<geometry_msgs::PoseWithCovarianceStamped> System::PoseQueue [private]

Definition at line 49 of file System.h.


Constructor & Destructor Documentation

Definition at line 23 of file System.cc.


Member Function Documentation

template<class T >
bool System::findClosest ( const ros::Time timestamp,
std::queue< T > &  queue,
T *  obj,
const double &  max_delay = 0.01 
) [private]

finds object in queue with timestamp closest to timestamp. Requires that T has a std_msgs::header field named "header"

Definition at line 188 of file System.cc.

void System::GUICommandCallBack ( void *  ptr,
std::string  sCommand,
std::string  sParams 
) [static, private]

Definition at line 619 of file System.cc.

void System::imageCallback ( const sensor_msgs::ImageConstPtr &  img) [private]

Definition at line 90 of file System.cc.

void System::imuCallback ( const sensor_msgs::ImuConstPtr &  msg) [private]

Definition at line 180 of file System.cc.

void System::init ( const CVD::ImageRef &  size) [private]

Definition at line 51 of file System.cc.

void System::keyboardCallback ( const std_msgs::StringConstPtr &  kb_input) [private]

Definition at line 221 of file System.cc.

bool System::keyframesservice ( ptam_com::KeyFrame_srvRequest &  req,
ptam_com::KeyFrame_srvResponse &  resp 
) [private]

Definition at line 511 of file System.cc.

bool System::pointcloudservice ( ptam_com::PointCloudRequest &  req,
ptam_com::PointCloudResponse &  resp 
) [private]

Definition at line 443 of file System.cc.

void System::publishPoseAndInfo ( const std_msgs::Header header) [private]

Definition at line 267 of file System.cc.

void System::publishPreviewImage ( CVD::Image< CVD::byte > &  img,
const std_msgs::Header header 
) [private]

Definition at line 377 of file System.cc.

void System::quaternionToRotationMatrix ( const geometry_msgs::Quaternion &  q,
TooN::SO3< double > &  R 
) [private]

Definition at line 583 of file System.cc.

void System::Run ( )

Definition at line 79 of file System.cc.

bool System::transformPoint ( const std::string &  target_frame,
const std_msgs::Header header,
const geometry_msgs::Point t_in,
TooN::Vector< 3 > &  t_out 
) [private]

Definition at line 245 of file System.cc.

bool System::transformQuaternion ( const std::string &  target_frame,
const std_msgs::Header header,
const geometry_msgs::Quaternion &  q_in,
TooN::SO3< double > &  r_out 
) [private]

Definition at line 225 of file System.cc.


Member Data Documentation

bool System::first_frame_ [private]

Definition at line 74 of file System.h.

Definition at line 56 of file System.h.

Definition at line 70 of file System.h.

CVD::Image<CVD::byte > System::img_bw_ [private]

Definition at line 79 of file System.h.

CVD::Image<CVD::Rgb<CVD::byte> > System::img_rgb_ [private]

Definition at line 80 of file System.h.

Definition at line 72 of file System.h.

Definition at line 76 of file System.h.

Definition at line 85 of file System.h.

Map* System::mpMap [private]

Definition at line 82 of file System.h.

Definition at line 83 of file System.h.

Definition at line 77 of file System.h.

Definition at line 84 of file System.h.

Definition at line 56 of file System.h.

Definition at line 66 of file System.h.

Definition at line 64 of file System.h.

Definition at line 65 of file System.h.

Definition at line 63 of file System.h.

Definition at line 68 of file System.h.

Definition at line 67 of file System.h.

Definition at line 58 of file System.h.

Definition at line 62 of file System.h.

Definition at line 57 of file System.h.

Definition at line 59 of file System.h.

Definition at line 60 of file System.h.

Definition at line 61 of file System.h.


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


ptam
Author(s): Markus Achtelik , Stephan Weiss , Simon Lynen
autogenerated on Sun Oct 5 2014 23:52:34