|
|
@ -1,11 +1,11 @@
|
|
|
|
#include "../include/qnode.hpp"
|
|
|
|
#include "../include/qnode.hpp"
|
|
|
|
|
|
|
|
|
|
|
|
#include "sensor_msgs/image_encodings.h"
|
|
|
|
#include "sensor_msgs/image_encodings.h"
|
|
|
|
|
|
|
|
#include <QtConcurrent/QtConcurrent>
|
|
|
|
|
|
|
|
|
|
|
|
QNode::QNode(int argc, char **argv) : init_argc(argc), init_argv(argv){
|
|
|
|
QNode::QNode(int argc, char **argv) : init_argc(argc), init_argv(argv){
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -25,7 +25,10 @@ bool QNode::init() {
|
|
|
|
qRegisterMetaType<sensor_msgs::BatteryState>("sensor_msgs::BatteryState");
|
|
|
|
qRegisterMetaType<sensor_msgs::BatteryState>("sensor_msgs::BatteryState");
|
|
|
|
ros::init(init_argc,init_argv,"Air_Ground_CEC",
|
|
|
|
ros::init(init_argc,init_argv,"Air_Ground_CEC",
|
|
|
|
ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
|
|
|
|
ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
|
|
|
|
SubAndPubTopic();
|
|
|
|
QtConcurrent::run([=](){
|
|
|
|
|
|
|
|
SubAndPubTopic();
|
|
|
|
|
|
|
|
});
|
|
|
|
|
|
|
|
|
|
|
|
//start();
|
|
|
|
//start();
|
|
|
|
return true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
@ -44,12 +47,13 @@ void QNode::SubAndPubTopic(){
|
|
|
|
&QNode::batteryCallback, this);
|
|
|
|
&QNode::batteryCallback, this);
|
|
|
|
|
|
|
|
|
|
|
|
image_transport::ImageTransport it(n);
|
|
|
|
image_transport::ImageTransport it(n);
|
|
|
|
image_sub0 = n.subscribe("camera/rgb/image_raw",100,&QNode::imageCallback,this);
|
|
|
|
image_sub = it.subscribe("camera/rgb/image_raw", 100, &QNode::imageCallback, this);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//image_sub0 = n.subscribe("camera/rgb/image_raw",100,&QNode::imageCallback,this)
|
|
|
|
|
|
|
|
|
|
|
|
//chatter_publisher = n.advertise<std_msgs::String>("chatter1", 1000);
|
|
|
|
//chatter_publisher = n.advertise<std_msgs::String>("chatter1", 1000);
|
|
|
|
//chatter_subscriber = n.subscribe("chatter",1000,&QNode::myCallback,this);
|
|
|
|
//chatter_subscriber = n.subscribe("chatter",1000,&QNode::myCallback,this);
|
|
|
|
|
|
|
|
ros::spin();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void QNode::batteryCallback(const sensor_msgs::BatteryState& message) {
|
|
|
|
void QNode::batteryCallback(const sensor_msgs::BatteryState& message) {
|
|
|
@ -161,35 +165,34 @@ void QNode::AutoMove(float speed_linear, float speed_turn,
|
|
|
|
|
|
|
|
|
|
|
|
ros::spinOnce();
|
|
|
|
ros::spinOnce();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
int i =0;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
//速度回调函数
|
|
|
|
//速度回调函数
|
|
|
|
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
|
|
|
|
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
|
|
std::cout<<i++<<endl;
|
|
|
|
|
|
|
|
ROS_INFO("i am ok");
|
|
|
|
|
|
|
|
emit speed_x(msg->twist.twist.linear.x);
|
|
|
|
emit speed_x(msg->twist.twist.linear.x);
|
|
|
|
emit speed_th(msg->twist.twist.angular.z);
|
|
|
|
emit speed_th(msg->twist.twist.angular.z);
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void QNode::imageCallback(const sensor_msgs::CompressedImageConstPtr &msg)
|
|
|
|
void QNode::imageCallback(const sensor_msgs::ImageConstPtr &msg)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
ROS_INFO("I'm setting picture in mul_t callback function!");
|
|
|
|
try
|
|
|
|
cv_bridge::CvImagePtr cv_ptr;
|
|
|
|
{
|
|
|
|
|
|
|
|
cv_bridge::CvImageConstPtr cv_ptr =
|
|
|
|
try {
|
|
|
|
cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
|
|
|
|
//深拷贝转换为opencv类型
|
|
|
|
cv::Mat img = cv_ptr->image;
|
|
|
|
cv_bridge::CvImagePtr cv_ptr_compressed =
|
|
|
|
QImage image = QImage(img.data,img.cols,img.rows,img.step[0],QImage::Format_RGB888);//change to QImage format
|
|
|
|
cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
|
|
|
|
//ROS_INFO("I'm setting picture in mul_t callback function!");
|
|
|
|
QImage im = Mat2QImage(cv_ptr_compressed->image);
|
|
|
|
//image.save("/home/jackyma/test.jpg");
|
|
|
|
emit show_image(im);
|
|
|
|
emit show_image(image);
|
|
|
|
} catch (cv_bridge::Exception& e) {
|
|
|
|
}
|
|
|
|
//log(Error, ("video frame0 exception: " + QString(e.what())).toStdString());
|
|
|
|
catch (cv_bridge::Exception& e)
|
|
|
|
return;
|
|
|
|
{
|
|
|
|
}
|
|
|
|
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
|
|
|
|
ros::spin();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|