#include <System.h>
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 ×tamp, 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_ |
| GLWindow2 * | mGLWindow |
| ATANCamera * | mpCamera |
| Map * | mpMap |
| MapMaker * | mpMapMaker |
| MapViewer * | mpMapViewer |
| Tracker * | mpTracker |
| 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_ |
typedef std::queue<sensor_msgs::Imu> System::ImuQueue [private] |
typedef std::queue<geometry_msgs::PoseWithCovarianceStamped> System::PoseQueue [private] |
| System::System | ( | ) |
| bool System::findClosest | ( | const ros::Time & | timestamp, |
| std::queue< T > & | queue, | ||
| T * | obj, | ||
| const double & | max_delay = 0.01 |
||
| ) | [private] |
| void System::GUICommandCallBack | ( | void * | ptr, |
| std::string | sCommand, | ||
| std::string | sParams | ||
| ) | [static, private] |
| void System::imageCallback | ( | const sensor_msgs::ImageConstPtr & | img | ) | [private] |
| void System::imuCallback | ( | const sensor_msgs::ImuConstPtr & | msg | ) | [private] |
| void System::init | ( | const CVD::ImageRef & | size | ) | [private] |
| void System::keyboardCallback | ( | const std_msgs::StringConstPtr & | kb_input | ) | [private] |
| bool System::keyframesservice | ( | ptam_com::KeyFrame_srvRequest & | req, |
| ptam_com::KeyFrame_srvResponse & | resp | ||
| ) | [private] |
| bool System::pointcloudservice | ( | ptam_com::PointCloudRequest & | req, |
| ptam_com::PointCloudResponse & | resp | ||
| ) | [private] |
| void System::publishPoseAndInfo | ( | const std_msgs::Header & | header | ) | [private] |
| void System::publishPreviewImage | ( | CVD::Image< CVD::byte > & | img, |
| const std_msgs::Header & | header | ||
| ) | [private] |
| void System::quaternionToRotationMatrix | ( | const geometry_msgs::Quaternion & | q, |
| TooN::SO3< double > & | R | ||
| ) | [private] |
| void System::Run | ( | ) |
| 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] |
| 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] |
bool System::first_frame_ [private] |
ros::NodeHandle System::image_nh_ [private] |
ros::CallbackQueue System::image_queue_ [private] |
CVD::Image<CVD::byte > System::img_bw_ [private] |
CVD::Image<CVD::Rgb<CVD::byte> > System::img_rgb_ [private] |
ImuQueue System::imu_msgs_ [private] |
GLWindow2* System::mGLWindow [private] |
ATANCamera* System::mpCamera [private] |
Map* System::mpMap [private] |
MapMaker* System::mpMapMaker [private] |
MapViewer* System::mpMapViewer [private] |
Tracker* System::mpTracker [private] |
ros::NodeHandle System::nh_ [private] |
ros::Publisher System::pub_info_ [private] |
ros::Publisher System::pub_pose_ [private] |
ros::Publisher System::pub_pose_world_ [private] |
image_transport::Publisher System::pub_preview_image_ [private] |
ros::ServiceServer System::srvKF_ [private] |
ros::ServiceServer System::srvPC_ [private] |
ros::Subscriber System::sub_calibration_ [private] |
image_transport::Subscriber System::sub_image_ [private] |
ros::Subscriber System::sub_imu_ [private] |
ros::Subscriber System::sub_kb_input_ [private] |
tf::TransformBroadcaster System::tf_pub_ [private] |
tf::TransformListener System::tf_sub_ [private] |