|
|
|
@ -1,6 +1,8 @@
|
|
|
|
|
#include "../include/Air_Ground_CEC/qnode.hpp"
|
|
|
|
|
|
|
|
|
|
#include "sensor_msgs/image_encodings.h"
|
|
|
|
|
#include "sensor_msgs/CompressedImage.h"
|
|
|
|
|
|
|
|
|
|
#include <QtConcurrent/QtConcurrent>
|
|
|
|
|
|
|
|
|
|
QNode::QNode(int argc, char **argv) : init_argc(argc), init_argv(argv){
|
|
|
|
@ -47,7 +49,8 @@ void QNode::SubAndPubTopic(){
|
|
|
|
|
&QNode::batteryCallback, this);
|
|
|
|
|
|
|
|
|
|
image_transport::ImageTransport it(n);
|
|
|
|
|
image_sub = it.subscribe("camera/rgb/image_raw", 100, &QNode::imageCallback, this);
|
|
|
|
|
//camera/rgb/image_raw
|
|
|
|
|
image_sub = it.subscribe("raspicam_node/image", 10, &QNode::imageCallback, this);
|
|
|
|
|
|
|
|
|
|
//image_sub0 = n.subscribe("camera/rgb/image_raw",100,&QNode::imageCallback,this)
|
|
|
|
|
|
|
|
|
@ -172,12 +175,12 @@ void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
|
|
|
|
|
{
|
|
|
|
|
emit speed_x(msg->twist.twist.linear.x);
|
|
|
|
|
emit speed_th(msg->twist.twist.angular.z);
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void QNode::imageCallback(const sensor_msgs::ImageConstPtr &msg)
|
|
|
|
|
{
|
|
|
|
|
ROS_INFO("i am ok");
|
|
|
|
|
try
|
|
|
|
|
{
|
|
|
|
|
cv_bridge::CvImageConstPtr cv_ptr =
|
|
|
|
|