1 #ifndef __THREAD_OPERATION_H__ 2 #define __THREAD_OPERATION_H__ 6 #include <boost/thread.hpp> 7 #include <boost/atomic.hpp> 8 #include <opencv2/opencv.hpp> 9 #include "armor_detect.h" 10 #include <logical_core/SetGoal.h> 11 #include <vision_unit/armor_msg.h> 12 #include <geometry_msgs/PoseStamped.h> 13 #include <geometry_msgs/PoseWithCovarianceStamped.h> 14 #include <move_base_msgs/MoveBaseAction.h> 15 #include <serial_comm/car_speed.h> 16 #include "armor_detect.h" 38 void pan_info_callback(
const serial_comm::car_speed::ConstPtr &pan_data);
51 void set_image_points(std::vector<cv::Point2f> armor_points);
59 cv::Mat m_img_buff[2];
62 ros::Subscriber sub_yaw;
63 ros::Publisher pub_armor_pos, pub_goal;
65 move_base_msgs::MoveBaseGoal goal;
66 move_base_msgs::MoveBaseGoal goal_pose;
68 cv::Mat camera_matrix;
72 std::vector<cv::Point3f> obj_p;
73 std::vector<cv::Point2f> img_p;
76 double ang_lim = 3.0/180*3.14;
77 double cam[9] = {839.923052, 0.0, 340.780730,
78 0.0, 837.671081, 261.766523,
81 double dist_c[5] = {0.082613, 0.043275, 0.002486, -0.000823, 0.0};
86 #endif // !__THREAD_OPERATION_H__ Definition: armor_detect.h:15
armor_info * get_armor()
Obtaining the armor information including the width and hight of the armor.
bool get_camera_num()
Maybe we have more than one camera, so we can use this function to get the camera No...
bool if_detected_armor()
If the program can detect an armor.
void running(void)
running the program of armor detect
Definition: armor_detect_node.h:23