rosrpp.h
Go to the documentation of this file.
1 
2 #include "fiducial_msgs/Fiducial.h"
3 #include "fiducial_msgs/FiducialTransform.h"
4 #include <sensor_msgs/CameraInfo.h>
5 
6 class RosRpp {
7  cv::Mat model;
8  cv::Mat ipts;
9  cv::Mat K;
10  cv::Mat dist;
11 
15  std::map<int, tf::Transform> frameTransforms;
19 
21  double fiducialLen;
22 
23  std::map<int, cv::Mat>prevRots;
24 
25 public:
26  RosRpp(double fiducialLen, bool doUndistort);
27 
28  bool fiducialCallback(fiducial_msgs::Fiducial* fiducial,
29  fiducial_msgs::FiducialTransform* transform);
30 
31  void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
32 };
std::map< int, cv::Mat > prevRots
Definition: rosrpp.h:23
ros::Subscriber verticesSub
Definition: rosrpp.h:17
cv::Mat dist
Definition: rosrpp.h:10
ros::Time frameTime
Definition: rosrpp.h:14
RosRpp(double fiducialLen, bool doUndistort)
Definition: calcPose.cpp:321
bool haveCamInfo
Definition: rosrpp.h:12
int currentFrame
Definition: rosrpp.h:13
bool fiducialCallback(fiducial_msgs::Fiducial *fiducial, fiducial_msgs::FiducialTransform *transform)
Definition: calcPose.cpp:94
double fiducialLen
Definition: rosrpp.h:21
bool doUndistort
Definition: rosrpp.h:20
std::map< int, tf::Transform > frameTransforms
Definition: rosrpp.h:15
ros::Subscriber camInfoSub
Definition: rosrpp.h:18
cv::Mat ipts
Definition: rosrpp.h:8
cv::Mat model
Definition: rosrpp.h:7
Definition: rosrpp.h:6
cv::Mat K
Definition: rosrpp.h:9
void camInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
Definition: calcPose.cpp:295
ros::Publisher tfPub
Definition: rosrpp.h:16


fiducial_pose
Author(s): Jim Vaughan
autogenerated on Thu Dec 28 2017 04:06:58