mirror of
https://github.com/chengyangkj/Ros_Qt5_Gui_App.git
synced 2025-09-15 12:58:58 +08:00
update
This commit is contained in:
parent
9e7b153ea2
commit
d9441b543d
@ -24,7 +24,7 @@ add_subdirectory(3rdpart/JsonStruct)
|
||||
add_subdirectory(common)
|
||||
add_subdirectory(basic)
|
||||
add_subdirectory(channel)
|
||||
# add_subdirectory(mainwindow)
|
||||
# add_subdirectory(core)
|
||||
add_subdirectory(mainwindow)
|
||||
add_subdirectory(core)
|
||||
|
||||
|
||||
|
||||
@ -1,15 +1,12 @@
|
||||
#pragma once
|
||||
namespace Msg {
|
||||
enum MsgId {
|
||||
kOccupancyMap = 0,
|
||||
kLocalCostMap = 1,
|
||||
kGlobalCostMap = 2,
|
||||
kRobotPose = 3,
|
||||
kLaserScan = 4,
|
||||
kLocalPath,
|
||||
kGlobalPath,
|
||||
kOdomPose,
|
||||
kSetNavGoalPose,
|
||||
kSetRelocPose,
|
||||
};
|
||||
} // namespace Msg
|
||||
#include "str_enum.h"
|
||||
|
||||
#define SOME_ENUM(OneValue) \
|
||||
OneValue(kOccupancyMap, ) OneValue(kLocalCostMap, ) \
|
||||
OneValue(kGlobalCostMap, ) OneValue(kRobotPose, ) OneValue(kLaserScan, ) \
|
||||
OneValue(kLocalPath, ) OneValue(kGlobalPath, ) OneValue(kOdomPose, ) \
|
||||
OneValue(kSetNavGoalPose, ) OneValue(kSetRelocPose, ) \
|
||||
OneValue(kSetRobotSpeed, )
|
||||
|
||||
DECLARE_ENUM(MsgId, SOME_ENUM)
|
||||
DEFINE_ENUM(MsgId, SOME_ENUM)
|
||||
|
||||
@ -14,6 +14,7 @@
|
||||
namespace basic {
|
||||
typedef OrientedPoint RobotPose;
|
||||
typedef std::vector<Point> RobotPath;
|
||||
typedef Eigen::Vector3d Color;
|
||||
struct RobotSpeed {
|
||||
double vx{0};
|
||||
double vy{0};
|
||||
|
||||
36
basic/str_enum.h
Normal file
36
basic/str_enum.h
Normal file
@ -0,0 +1,36 @@
|
||||
#pragma once
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <string>
|
||||
// expansion macro for enum value definition
|
||||
#define ENUM_VALUE(name, assign) name assign,
|
||||
|
||||
// expansion macro for enum to string conversion
|
||||
#define ENUM_CASE(name, assign) \
|
||||
case name: \
|
||||
return #name;
|
||||
|
||||
// expansion macro for string to enum conversion
|
||||
#define ENUM_STRCMP(name, assign) \
|
||||
if (!strcmp(str, #name)) \
|
||||
return name;
|
||||
|
||||
/// declare the access function and define enum values
|
||||
#define DECLARE_ENUM(EnumType, ENUM_DEF) \
|
||||
enum EnumType { ENUM_DEF(ENUM_VALUE) }; \
|
||||
inline const std::string ToString(enum EnumType dummy); \
|
||||
inline enum EnumType Get##EnumType##Value(const char *str);
|
||||
|
||||
/// define the access function names
|
||||
#define DEFINE_ENUM(EnumType, ENUM_DEF) \
|
||||
const std::string ToString(enum EnumType value) { \
|
||||
switch (value) { \
|
||||
ENUM_DEF(ENUM_CASE) \
|
||||
default: \
|
||||
return ""; /* handle input error */ \
|
||||
} \
|
||||
} \
|
||||
enum EnumType Get##EnumType##Value(const char *str) { \
|
||||
ENUM_DEF(ENUM_STRCMP) \
|
||||
return (enum EnumType)0; /* handle input error */ \
|
||||
}
|
||||
@ -74,8 +74,7 @@ void ChannelManager::CloseChannel() {
|
||||
delete channel_ptr_;
|
||||
channel_ptr_ = nullptr;
|
||||
}
|
||||
void ChannelManager::SendMessage(const Msg::MsgId &msg_id,
|
||||
const std::any &msg) {
|
||||
void ChannelManager::SendMessage(const MsgId &msg_id, const std::any &msg) {
|
||||
if (channel_ptr_ != nullptr) {
|
||||
channel_ptr_->SendMessage(msg_id, msg);
|
||||
}
|
||||
|
||||
@ -13,7 +13,6 @@
|
||||
#include <any>
|
||||
#include <boost/dll/import.hpp>
|
||||
#include <boost/filesystem.hpp>
|
||||
using namespace Msg;
|
||||
class ChannelManager {
|
||||
private:
|
||||
VirtualChannelNode *channel_ptr_{nullptr};
|
||||
@ -23,11 +22,11 @@ public:
|
||||
explicit ChannelManager();
|
||||
~ChannelManager();
|
||||
/// @brief 传入channel so路径,打开对应的通信channel
|
||||
/// @param name
|
||||
/// @return
|
||||
/// @param name
|
||||
/// @return
|
||||
bool OpenChannel(const std::string &name);
|
||||
/// @brief 自动查找当前可执行程序陆军下的lib目录中的channel并打开
|
||||
/// @return
|
||||
/// @return
|
||||
bool OpenChannelAuto();
|
||||
/// @brief 查找lib路径下所有channel
|
||||
/// @return channel list
|
||||
@ -40,6 +39,5 @@ public:
|
||||
}
|
||||
void CloseChannel();
|
||||
|
||||
void SendMessage(const Msg::MsgId &msg_id,
|
||||
const std::any &msg);
|
||||
void SendMessage(const MsgId &msg_id, const std::any &msg);
|
||||
};
|
||||
@ -75,16 +75,16 @@ bool rclcomm::Stop() {
|
||||
rclcpp::shutdown();
|
||||
return true;
|
||||
}
|
||||
void rclcomm::SendMessage(const Msg::MsgId &msg_id, const std::any &msg) {
|
||||
void rclcomm::SendMessage(const MsgId &msg_id, const std::any &msg) {
|
||||
switch (msg_id) {
|
||||
case Msg::MsgId::kSetNavGoalPose: {
|
||||
case MsgId::kSetNavGoalPose: {
|
||||
auto pose = std::any_cast<basic::RobotPose>(msg);
|
||||
std::cout << "recv nav goal pose:" << pose << std::endl;
|
||||
|
||||
PubNavGoal(pose);
|
||||
|
||||
} break;
|
||||
case Msg::MsgId::kSetRelocPose: {
|
||||
case MsgId::kSetRelocPose: {
|
||||
auto pose = std::any_cast<basic::RobotPose>(msg);
|
||||
std::cout << "recv reloc pose:" << pose << std::endl;
|
||||
PubRelocPose(pose);
|
||||
@ -282,29 +282,30 @@ void rclcomm::localCostMapCallback(
|
||||
cost_map(x, y) = msg->data[i];
|
||||
}
|
||||
cost_map.SetFlip();
|
||||
OnDataCallback(MsgId::kGlobalCostMap, cost_map);
|
||||
// map_image.save("/home/chengyangkj/test.jpg");
|
||||
try {
|
||||
// 坐标变换 将局部代价地图的基础坐标转换为map下 进行绘制显示
|
||||
geometry_msgs::msg::PoseStamped pose_map_frame;
|
||||
geometry_msgs::msg::PoseStamped pose_curr_frame;
|
||||
pose_curr_frame.pose.position.x = origin_x;
|
||||
pose_curr_frame.pose.position.y = origin_y;
|
||||
q.setRPY(0, 0, origin_theta);
|
||||
pose_curr_frame.pose.orientation = tf2::toMsg(q);
|
||||
pose_curr_frame.header.frame_id = msg->header.frame_id;
|
||||
tf_buffer_->transform(pose_curr_frame, pose_map_frame, "map");
|
||||
tf2::fromMsg(pose_map_frame.pose.orientation, q);
|
||||
tf2::Matrix3x3 mat(q);
|
||||
double roll, pitch, yaw;
|
||||
mat.getRPY(roll, pitch, yaw);
|
||||
// try {
|
||||
// // 坐标变换 将局部代价地图的基础坐标转换为map下 进行绘制显示
|
||||
// geometry_msgs::msg::PoseStamped pose_map_frame;
|
||||
// geometry_msgs::msg::PoseStamped pose_curr_frame;
|
||||
// pose_curr_frame.pose.position.x = origin_x;
|
||||
// pose_curr_frame.pose.position.y = origin_y;
|
||||
// q.setRPY(0, 0, origin_theta);
|
||||
// pose_curr_frame.pose.orientation = tf2::toMsg(q);
|
||||
// pose_curr_frame.header.frame_id = msg->header.frame_id;
|
||||
// tf_buffer_->transform(pose_curr_frame, pose_map_frame, "map");
|
||||
// tf2::fromMsg(pose_map_frame.pose.orientation, q);
|
||||
// tf2::Matrix3x3 mat(q);
|
||||
// double roll, pitch, yaw;
|
||||
// mat.getRPY(roll, pitch, yaw);
|
||||
|
||||
basic::RobotPose localCostmapPose;
|
||||
localCostmapPose.x = pose_map_frame.pose.position.x;
|
||||
localCostmapPose.y = pose_map_frame.pose.position.y + cost_map.heightMap();
|
||||
localCostmapPose.theta = yaw;
|
||||
// emit emitUpdateLocalCostMap(cost_map, localCostmapPose);
|
||||
} catch (tf2::TransformException &ex) {
|
||||
}
|
||||
// basic::RobotPose localCostmapPose;
|
||||
// localCostmapPose.x = pose_map_frame.pose.position.x;
|
||||
// localCostmapPose.y = pose_map_frame.pose.position.y + cost_map.heightMap();
|
||||
// localCostmapPose.theta = yaw;
|
||||
// // emit emitUpdateLocalCostMap(cost_map, localCostmapPose);
|
||||
// } catch (tf2::TransformException &ex) {
|
||||
// }
|
||||
}
|
||||
void rclcomm::map_callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg) {
|
||||
double origin_x = msg->info.origin.position.x;
|
||||
|
||||
@ -52,7 +52,7 @@ public:
|
||||
void PubNavGoal(const RobotPose &pose) override;
|
||||
void PubRobotSpeed(const RobotSpeed &speed) override;
|
||||
basic::RobotPose getTrasnsform(std::string from, std::string to);
|
||||
void SendMessage(const Msg::MsgId &msg_id, const std::any &msg) override;
|
||||
void SendMessage(const MsgId &msg_id, const std::any &msg) override;
|
||||
|
||||
private:
|
||||
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr _publisher;
|
||||
|
||||
@ -10,10 +10,4 @@ TEST(ChannelManager, OpenDL) {
|
||||
}));
|
||||
manager.SendMessage(MsgId::kSetNavGoalPose,
|
||||
basic::RobotPose(0.1, 0.001, 0.1));
|
||||
auto th = std::thread([] {
|
||||
while (1) {
|
||||
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||
}
|
||||
});
|
||||
th.join();
|
||||
}
|
||||
@ -1,3 +0,0 @@
|
||||
// #include "rclcomm.h"
|
||||
#include <gtest/gtest.h>
|
||||
TEST(ChannelRos2Test, Open) { }
|
||||
@ -14,7 +14,6 @@
|
||||
#include <any>
|
||||
#include <thread>
|
||||
using namespace basic;
|
||||
using namespace Msg;
|
||||
class VirtualChannelNode {
|
||||
|
||||
public:
|
||||
@ -61,5 +60,5 @@ public:
|
||||
std::function<void(const MsgId &id, const std::any &data)> OnDataCallback;
|
||||
int loop_rate_{30};
|
||||
std::atomic_bool run_flag_{false};
|
||||
virtual void SendMessage(const Msg::MsgId &msg_id, const std::any &msg){};
|
||||
virtual void SendMessage(const MsgId &msg_id, const std::any &msg){};
|
||||
};
|
||||
|
||||
@ -1,7 +1,37 @@
|
||||
#pragma once
|
||||
#include "easylogging++.h"
|
||||
|
||||
static void InitLogger() {
|
||||
|
||||
el::Configurations defaultConf;
|
||||
defaultConf.setToDefault();
|
||||
//设置最大文件大小
|
||||
defaultConf.setGlobally(el::ConfigurationType::MaxLogFileSize, "1000000");
|
||||
//是否写入文件
|
||||
defaultConf.setGlobally(el::ConfigurationType::ToFile, "true");
|
||||
//是否输出控制台
|
||||
defaultConf.setGlobally(el::ConfigurationType::ToStandardOutput, "false");
|
||||
// filename
|
||||
defaultConf.setGlobally(el::ConfigurationType::Filename,
|
||||
"ros_qt_gui_app.log");
|
||||
//设置配置文件
|
||||
el::Loggers::reconfigureLogger("default", defaultConf);
|
||||
|
||||
/// 防止Fatal级别日志中断程序
|
||||
el::Loggers::addFlag(el::LoggingFlag::DisableApplicationAbortOnFatalLog);
|
||||
|
||||
/// 选择划分级别的日志
|
||||
el::Loggers::addFlag(el::LoggingFlag::HierarchicalLogging);
|
||||
|
||||
/// 设置级别门阀值,修改参数可以控制日志输出
|
||||
el::Loggers::setLoggingLevel(el::Level::Global);
|
||||
}
|
||||
#ifndef LOGGER_INFO
|
||||
#define LOGGER_INFO(str) LOG(INFO) << str;
|
||||
#define LOGGER_INFO(str) \
|
||||
{ \
|
||||
std::cout << str << std::endl; \
|
||||
LOG(INFO) << str; \
|
||||
}
|
||||
#endif
|
||||
#ifndef LOGGER_ERROR
|
||||
#define LOGGER_ERROR(str) LOG(ERROR) << str;
|
||||
|
||||
@ -1,9 +1,12 @@
|
||||
|
||||
file(GLOB_RECURSE SOURCE_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} src/*.cpp src/*.cc)
|
||||
file(GLOB_RECURSE UI_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} ui/*.ui)
|
||||
file(GLOB_RECURSE QRC_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} resource/*.qrc)
|
||||
file(GLOB_RECURSE INCLUDE_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} include/*.h *.hpp)
|
||||
file(GLOB_RECURSE SOURCE_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} ./*.cpp ./*.cc)
|
||||
file(GLOB_RECURSE INCLUDE_FILE CONFIGURE_DEPENDS ${CMAKE_SOURCE_DIR} ./*.h ./*.hpp)
|
||||
find_package(Qt5 COMPONENTS Widgets REQUIRED)
|
||||
add_executable(
|
||||
${PROJECT_NAME} main.cpp)
|
||||
${PROJECT_NAME} ${SOURCE_FILE})
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} common mainwindow)
|
||||
target_link_libraries(${PROJECT_NAME} common mainwindow Qt5::Core Qt5::Widgets)
|
||||
set_target_properties(${PROJECT_NAME} PROPERTIES
|
||||
RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}"
|
||||
LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/lib"
|
||||
)
|
||||
@ -5,8 +5,8 @@
|
||||
* @LastEditTime: 2023-10-05 11:39:01
|
||||
* @FilePath: /ROS2_Qt5_Gui_App/src/main.cpp
|
||||
*/
|
||||
#include "logger/easylogging++.h"
|
||||
#include "mainwindow.h"
|
||||
#include "logger/logger.h"
|
||||
#include "runtime/application_manager.h"
|
||||
#include <QApplication>
|
||||
#include <QLabel>
|
||||
#include <QMovie>
|
||||
@ -14,52 +14,11 @@
|
||||
#include <QSplashScreen>
|
||||
#include <QThread>
|
||||
#include <iostream>
|
||||
INITIALIZE_EASYLOGGINGPP
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
QApplication a(argc, argv);
|
||||
//启动动画
|
||||
QPixmap pixmap("://background/loding5.gif");
|
||||
QSplashScreen splash(pixmap);
|
||||
splash.setWindowOpacity(1); // 设置窗口透明度
|
||||
QLabel label(&splash);
|
||||
QMovie mv("://background/loding5.gif");
|
||||
label.setMovie(&mv);
|
||||
mv.start();
|
||||
splash.show();
|
||||
splash.setCursor(Qt::BlankCursor);
|
||||
for (int i = 0; i < 2000; i += mv.speed()) {
|
||||
a.processEvents(); //使程序在显示启动画面的同时仍能响应鼠标等其他事件
|
||||
QThread::msleep(50); // 延时
|
||||
}
|
||||
|
||||
// logger
|
||||
el::Configurations defaultConf;
|
||||
defaultConf.setToDefault();
|
||||
//设置最大文件大小
|
||||
defaultConf.setGlobally(el::ConfigurationType::MaxLogFileSize, "1000000");
|
||||
//是否写入文件
|
||||
defaultConf.setGlobally(el::ConfigurationType::ToFile, "true");
|
||||
//是否输出控制台
|
||||
defaultConf.setGlobally(el::ConfigurationType::ToStandardOutput, "false");
|
||||
// filename
|
||||
defaultConf.setGlobally(el::ConfigurationType::Filename,
|
||||
"ros_qt_gui_app.log");
|
||||
//设置配置文件
|
||||
el::Loggers::reconfigureLogger("default", defaultConf);
|
||||
|
||||
/// 防止Fatal级别日志中断程序
|
||||
el::Loggers::addFlag(el::LoggingFlag::DisableApplicationAbortOnFatalLog);
|
||||
|
||||
/// 选择划分级别的日志
|
||||
el::Loggers::addFlag(el::LoggingFlag::HierarchicalLogging);
|
||||
|
||||
/// 设置级别门阀值,修改参数可以控制日志输出
|
||||
el::Loggers::setLoggingLevel(el::Level::Global);
|
||||
LOG(INFO) << "ros qt5 gui app init";
|
||||
|
||||
CMainWindow w;
|
||||
w.show();
|
||||
splash.finish(&w); //在主体对象初始化完成后结束启动动画
|
||||
ApplicationManager manager_;
|
||||
LOGGER_INFO("ros_qt5_gui_app init!")
|
||||
return a.exec();
|
||||
}
|
||||
|
||||
9
core/runtime/application_manager.cc
Normal file
9
core/runtime/application_manager.cc
Normal file
@ -0,0 +1,9 @@
|
||||
#include "application_manager.h"
|
||||
#include "logger/logger.h"
|
||||
INITIALIZE_EASYLOGGINGPP; // logger
|
||||
ApplicationManager::ApplicationManager(/* args */) {
|
||||
InitLogger();
|
||||
main_window.show();
|
||||
}
|
||||
|
||||
ApplicationManager::~ApplicationManager() {}
|
||||
10
core/runtime/application_manager.h
Normal file
10
core/runtime/application_manager.h
Normal file
@ -0,0 +1,10 @@
|
||||
#pragma once
|
||||
#include "mainwindow.h"
|
||||
class ApplicationManager {
|
||||
private:
|
||||
MainWindow main_window;
|
||||
|
||||
public:
|
||||
ApplicationManager(/* args */);
|
||||
~ApplicationManager();
|
||||
};
|
||||
@ -28,5 +28,5 @@ target_include_directories(
|
||||
include/
|
||||
${CMAKE_CURRENT_BINARY_DIR}
|
||||
)
|
||||
target_link_libraries(${TARGET_NAME} Qt5::Widgets qt${QT_VERSION_MAJOR}advanceddocking json_struct common basic channel channel_ros2)
|
||||
target_link_libraries(${TARGET_NAME} Qt5::Widgets qt${QT_VERSION_MAJOR}advanceddocking json_struct common basic channel)
|
||||
|
||||
|
||||
@ -1,15 +1,5 @@
|
||||
#pragma once
|
||||
|
||||
namespace Display {
|
||||
using LaserDataMap = std::map<int, std::vector<Eigen::Vector2f>>;
|
||||
using LaserData = std::vector<Eigen::Vector2f>;
|
||||
using LaserColorMap = std::map<int, QColor>;
|
||||
using ParticlePointsType = std::vector<Eigen::Vector3f>;
|
||||
using RangeVec = Eigen::Vector4f; // xmin,ymin,xmax,ymax
|
||||
using Pose3f = Eigen::Vector3f;
|
||||
using Point2f = Eigen::Vector2f;
|
||||
using PathData = std::vector<Point2f>;
|
||||
using RegionDataMap = std::map<std::string, std::vector<RangeVec>>;
|
||||
using TagDataMap = std::map<std::string, Pose3f>;
|
||||
using Color =Eigen::Vector3f;
|
||||
|
||||
} // namespace Display
|
||||
|
||||
@ -22,7 +22,6 @@ private:
|
||||
void drawFrame(QPainter *painter);
|
||||
|
||||
public:
|
||||
Display::ParticlePointsType particle_data_;
|
||||
DisplayDemo(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name = "");
|
||||
~DisplayDemo();
|
||||
|
||||
@ -14,12 +14,10 @@
|
||||
#include "display_cost_map.h"
|
||||
#include "display_occ_map.h"
|
||||
#include "display_path.h"
|
||||
#include "display_tag.h"
|
||||
#include "factory_display.h"
|
||||
#include "laser_points.h"
|
||||
#include "particle_points.h"
|
||||
#include "msg/msg_info.h"
|
||||
#include "point_shape.h"
|
||||
#include "region.h"
|
||||
#include "widgets/set_pose_widget.h"
|
||||
#include <Eigen/Dense>
|
||||
#include <QGraphicsScene>
|
||||
@ -30,13 +28,13 @@
|
||||
#include <any>
|
||||
#include <functional>
|
||||
#include <map>
|
||||
#define DISPLAY_ROBOT "Robot"
|
||||
#define DISPLAY_MAP "OccupyMap"
|
||||
#define DISPLAY_LOCAL_COST_MAP "LocalCostMap"
|
||||
#define DISPLAY_GLOBAL_COST_MAP "GlobalCostMap"
|
||||
#define DISPLAY_GLOBAL_PATH "GlobalPath"
|
||||
#define DISPLAY_LOCAL_PATH "LocalPath"
|
||||
#define DISPLAY_LASER "LaserScan"
|
||||
#define DISPLAY_ROBOT ToString(MsgId::kRobotPose)
|
||||
#define DISPLAY_MAP ToString(MsgId::kOccupancyMap)
|
||||
#define DISPLAY_LOCAL_COST_MAP ToString(MsgId::kLocalCostMap)
|
||||
#define DISPLAY_GLOBAL_COST_MAP ToString(MsgId::kGlobalCostMap)
|
||||
#define DISPLAY_GLOBAL_PATH ToString(MsgId::kGlobalPath)
|
||||
#define DISPLAY_LOCAL_PATH ToString(MsgId::kLocalPath)
|
||||
#define DISPLAY_LASER ToString(MsgId::kLaserScan)
|
||||
#define DISPLAY_PARTICLE "Particle"
|
||||
#define DISPLAY_REGION "Region"
|
||||
#define DISPLAY_TAG "Tag"
|
||||
@ -44,15 +42,14 @@
|
||||
|
||||
// group
|
||||
#define GROUP_MAP "Group_Map"
|
||||
|
||||
namespace Display {
|
||||
class DisplayManager : public QObject {
|
||||
Q_OBJECT
|
||||
private:
|
||||
std::map<std::string, std::any> display_map_;
|
||||
|
||||
Eigen::Vector3f robot_pose_{0, 0, 0};
|
||||
Eigen::Vector3f robot_pose_goal_{0, 0, 0};
|
||||
RobotPose robot_pose_{0, 0, 0};
|
||||
RobotPose robot_pose_goal_{0, 0, 0};
|
||||
OccupancyMap map_data_;
|
||||
std::string focus_display_;
|
||||
RobotPose local_cost_world_pose_;
|
||||
@ -64,7 +61,6 @@ private:
|
||||
SetPoseWidget *set_nav_pose_widget_;
|
||||
signals:
|
||||
void cursorPosMap(QPointF);
|
||||
void DisplayRobotPoseWorld(Eigen::Vector3f pose);
|
||||
void signalPub2DPose(const RobotPose &pose);
|
||||
void signalPub2DGoal(const RobotPose &pose);
|
||||
public slots:
|
||||
@ -75,25 +71,25 @@ public slots:
|
||||
void slotNavGoalScenePoseChanged(const RobotPose &pose);
|
||||
void slotSetRobotPose(const RobotPose &pose);
|
||||
void slotSetNavPose(const RobotPose &pose);
|
||||
void UpdateTopicData(const MsgId &id, const std::any &data);
|
||||
|
||||
private:
|
||||
Eigen::Vector3f wordPose2Scene(const Eigen::Vector3f &point);
|
||||
QPointF wordPose2Scene(const QPointF &point);
|
||||
QPointF wordPose2Map(const QPointF &pose);
|
||||
void FocusDisplay(const std::string &display_name);
|
||||
void InitUi();
|
||||
std::vector<Eigen::Vector2f>
|
||||
transLaserPoint(const std::vector<Eigen::Vector2f> &point);
|
||||
std::vector<Point> transLaserPoint(const std::vector<Point> &point);
|
||||
QPushButton *btn_move_focus_;
|
||||
|
||||
public:
|
||||
DisplayManager(QGraphicsView *viewer);
|
||||
~DisplayManager();
|
||||
VirtualDisplay *GetDisplay(const std::string &name);
|
||||
QPointF wordPose2Scene(const QPointF &point);
|
||||
RobotPose wordPose2Scene(const RobotPose &point);
|
||||
QPointF wordPose2Map(const QPointF &pose);
|
||||
RobotPose wordPose2Map(const RobotPose &pose);
|
||||
bool UpdateDisplay(const std::string &display_name, const std::any &data);
|
||||
void UpdateRobotPose(const Eigen::Vector3f &pose);
|
||||
void UpdateRobotPose(const RobotPose &pose);
|
||||
bool SetDisplayConfig(const std::string &config_name, const std::any &data);
|
||||
Eigen::Vector3f wordPose2Map(const Eigen::Vector3f &pose);
|
||||
void SetRelocMode(bool is_move);
|
||||
void SetNavGoalMode(bool is_start);
|
||||
|
||||
|
||||
@ -15,7 +15,7 @@
|
||||
#include <QGraphicsSceneWheelEvent>
|
||||
|
||||
#include "virtual_display.h"
|
||||
|
||||
using namespace basic;
|
||||
namespace Display {
|
||||
class DisplayPath : public VirtualDisplay {
|
||||
private:
|
||||
@ -25,7 +25,7 @@ private:
|
||||
private:
|
||||
void drawPath(QPainter *painter);
|
||||
|
||||
void computeBoundRect(const Display::PathData &path);
|
||||
void computeBoundRect(const RobotPath &path);
|
||||
|
||||
public:
|
||||
DisplayPath(const std::string &display_name, const int &z_value,
|
||||
|
||||
@ -1,25 +0,0 @@
|
||||
#ifndef DISPLAY_TAG
|
||||
#define DISPLAY_TAG
|
||||
#include <Eigen/Dense>
|
||||
#include <QColor>
|
||||
#include <QGraphicsItem>
|
||||
#include <QGraphicsSceneWheelEvent>
|
||||
|
||||
#include "virtual_display.h"
|
||||
|
||||
namespace Display {
|
||||
class DisplayTag : public VirtualDisplay {
|
||||
|
||||
public:
|
||||
Display::TagDataMap tag_data_;
|
||||
QPixmap tag_image_;
|
||||
DisplayTag(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name = "");
|
||||
~DisplayTag();
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget = nullptr) override;
|
||||
bool UpdateData(const std::any &data) override;
|
||||
void computeBoundRect(Display::TagDataMap &data_map);
|
||||
};
|
||||
} // namespace Display
|
||||
#endif
|
||||
@ -6,12 +6,12 @@
|
||||
#include <QGraphicsSceneWheelEvent>
|
||||
|
||||
#include "virtual_display.h"
|
||||
using namespace basic;
|
||||
namespace Display {
|
||||
class LaserPoints : public VirtualDisplay {
|
||||
public:
|
||||
QColor laser_color_;
|
||||
Display::LaserDataMap laser_data_map_;
|
||||
Display::LaserDataMap laser_data_scene_;
|
||||
std::map<int, std::vector<Point>> laser_data_scene_;
|
||||
LaserPoints(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name = "");
|
||||
~LaserPoints();
|
||||
@ -23,9 +23,11 @@ public:
|
||||
|
||||
private:
|
||||
void Id2Color(int id, int &R, int &G, int &B);
|
||||
void drawLaser(QPainter *painter, int id, std::vector<Eigen::Vector2f>);
|
||||
void computeBoundRect(const Display::LaserDataMap &laser_scan);
|
||||
Display::LaserColorMap location_to_color_;
|
||||
void drawLaser(QPainter *painter, int id, std::vector<Point>);
|
||||
void computeBoundRect(const std::map<int, std::vector<Point>> &laser_scan);
|
||||
|
||||
private:
|
||||
std::map<int, QColor> location_to_color_;
|
||||
};
|
||||
} // namespace Display
|
||||
#endif
|
||||
|
||||
@ -1,35 +0,0 @@
|
||||
/*
|
||||
* @Author: chengyang chengyangkj@outlook.com
|
||||
* @Date: 2023-04-11 10:13:22
|
||||
* @LastEditors: chengyang chengyangkj@outlook.com
|
||||
* @LastEditTime: 2023-04-20 17:02:58
|
||||
* @FilePath:
|
||||
* ////include/display/display_demo.h
|
||||
* @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置
|
||||
* 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
|
||||
*/
|
||||
#ifndef PARTICLE_POINTS_H
|
||||
#define PARTICLE_POINTS_H
|
||||
#include <Eigen/Dense>
|
||||
#include <QColor>
|
||||
#include <QGraphicsItem>
|
||||
#include <QGraphicsSceneWheelEvent>
|
||||
|
||||
#include "virtual_display.h"
|
||||
namespace Display {
|
||||
class ParticlePoints : public VirtualDisplay {
|
||||
private:
|
||||
void drawParticle(QPainter *painter, Display::ParticlePointsType particle);
|
||||
|
||||
public:
|
||||
Display::ParticlePointsType particle_data_;
|
||||
ParticlePoints(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name = "");
|
||||
~ParticlePoints();
|
||||
void computeBoundRect(const Display::ParticlePointsType &particle);
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget = nullptr) override;
|
||||
bool UpdateData(const std::any &data) override;
|
||||
};
|
||||
} // namespace Display
|
||||
#endif
|
||||
@ -1,33 +0,0 @@
|
||||
/*
|
||||
* @Author: chengyang chengyangkj@outlook.com
|
||||
* @Date: 2023-04-11 10:13:22
|
||||
* @LastEditors: chengyang chengyangkj@outlook.com
|
||||
* @LastEditTime: 2023-05-09 11:42:35
|
||||
* @FilePath:
|
||||
* ////include/display/display_demo.h
|
||||
* @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置
|
||||
* 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
|
||||
*/
|
||||
#ifndef DISPLAY_DEMO_H
|
||||
#define DISPLAY_DEMO_H
|
||||
#include <Eigen/Dense>
|
||||
#include <QColor>
|
||||
#include <QGraphicsItem>
|
||||
#include <QGraphicsSceneWheelEvent>
|
||||
|
||||
#include "virtual_display.h"
|
||||
namespace Display {
|
||||
class Region : public VirtualDisplay {
|
||||
|
||||
public:
|
||||
Display::RegionDataMap region_data_;
|
||||
Region(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name = "");
|
||||
~Region();
|
||||
void computeBoundRect(Display::RegionDataMap &data_map);
|
||||
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget = nullptr) override;
|
||||
bool UpdateData(const std::any &data) override;
|
||||
};
|
||||
} // namespace Display
|
||||
#endif
|
||||
@ -1,12 +1,12 @@
|
||||
#ifndef MAINWINDOW_H
|
||||
#define MAINWINDOW_H
|
||||
|
||||
#include "point_type.h"
|
||||
#include "DockAreaWidget.h"
|
||||
#include "DockManager.h"
|
||||
#include "DockWidget.h"
|
||||
#include "channel_instance.h"
|
||||
#include "channel_manager.h"
|
||||
#include "display/display_manager.h"
|
||||
#include "point_type.h"
|
||||
#include "widgets/dashboard.h"
|
||||
#include "widgets/set_pose_widget.h"
|
||||
#include "widgets/speed_ctrl.h"
|
||||
@ -33,26 +33,20 @@
|
||||
#include <QWidgetAction>
|
||||
QT_BEGIN_NAMESPACE
|
||||
namespace Ui {
|
||||
class CMainWindow;
|
||||
class MainWindow;
|
||||
}
|
||||
QT_END_NAMESPACE
|
||||
|
||||
class CMainWindow : public QMainWindow {
|
||||
class MainWindow : public QMainWindow {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
CMainWindow(QWidget *parent = nullptr);
|
||||
~CMainWindow();
|
||||
MainWindow(QWidget *parent = nullptr);
|
||||
~MainWindow();
|
||||
public slots:
|
||||
void onRecvData(QString);
|
||||
void updateOdomInfo(RobotState);
|
||||
void slotUpdateRobotPose(RobotPose pose);
|
||||
void slotUpdateLaserPoint(LaserScan scan);
|
||||
void updateGlobalPath(RobotPath path);
|
||||
void updateLocalPath(RobotPath path);
|
||||
void updateLocalCostMap(CostMap, RobotPose);
|
||||
void updateGlobalCostMap(CostMap map);
|
||||
void signalCursorPose(QPointF pos);
|
||||
void SendChannelMsg(const MsgId &id, const std::any &data);
|
||||
void updateOdomInfo(RobotState state);
|
||||
|
||||
protected:
|
||||
virtual void closeEvent(QCloseEvent *event) override;
|
||||
@ -61,8 +55,8 @@ private:
|
||||
QAction *SavePerspectiveAction = nullptr;
|
||||
QWidgetAction *PerspectiveListAction = nullptr;
|
||||
QComboBox *PerspectiveComboBox = nullptr;
|
||||
|
||||
Ui::CMainWindow *ui;
|
||||
ChannelManager channel_manager_;
|
||||
Ui::MainWindow *ui;
|
||||
DashBoard *speed_dash_board_;
|
||||
ads::CDockManager *dock_manager_;
|
||||
ads::CDockAreaWidget *StatusDockArea;
|
||||
@ -75,9 +69,15 @@ private:
|
||||
SpeedCtrlWidget *speed_ctrl_widget_;
|
||||
StatusBarWidget *status_bar_widget_;
|
||||
ToolsBarWidget *tools_bar_widget_;
|
||||
signals:
|
||||
void OnRecvChannelData(const MsgId &id, const std::any &data);
|
||||
|
||||
private:
|
||||
void setupUi();
|
||||
bool openChannel();
|
||||
bool openChannel(const std::string &channel_name);
|
||||
void closeChannel();
|
||||
void registerChannel();
|
||||
private slots:
|
||||
void savePerspective();
|
||||
};
|
||||
|
||||
@ -20,7 +20,7 @@ void DisplayDemo::paint(QPainter *painter,
|
||||
DisplayDemo::~DisplayDemo() {}
|
||||
bool DisplayDemo::UpdateData(const std::any &data) {
|
||||
try {
|
||||
particle_data_ = std::any_cast<Display::ParticlePointsType>(data);
|
||||
|
||||
update();
|
||||
} catch (const std::bad_any_cast &e) {
|
||||
std::cout << e.what() << '\n';
|
||||
|
||||
@ -28,16 +28,13 @@ DisplayManager::DisplayManager(QGraphicsView *viewer)
|
||||
->SetMoveEnable(true)
|
||||
->setVisible(false);
|
||||
new LaserPoints(DISPLAY_LASER, 2, DISPLAY_MAP);
|
||||
new ParticlePoints(DISPLAY_PARTICLE, 4, DISPLAY_MAP);
|
||||
new Region(DISPLAY_REGION, 3);
|
||||
new DisplayTag(DISPLAY_TAG, 4);
|
||||
new DisplayPath(DISPLAY_GLOBAL_PATH, 6, DISPLAY_MAP);
|
||||
new DisplayPath(DISPLAY_LOCAL_PATH, 6, DISPLAY_MAP);
|
||||
|
||||
// defalut display config
|
||||
|
||||
SetDisplayConfig(DISPLAY_GLOBAL_PATH "/Color", Display::Color(0, 0, 255));
|
||||
SetDisplayConfig(DISPLAY_LOCAL_PATH "/Color", Display::Color(0, 255, 0));
|
||||
SetDisplayConfig(DISPLAY_GLOBAL_PATH + "/Color", Color(0, 0, 255));
|
||||
SetDisplayConfig(DISPLAY_LOCAL_PATH + "/Color", Color(0, 255, 0));
|
||||
|
||||
// connection
|
||||
|
||||
@ -50,9 +47,12 @@ DisplayManager::DisplayManager(QGraphicsView *viewer)
|
||||
FactoryDisplay::Instance()->SetMoveEnable(DISPLAY_MAP);
|
||||
InitUi();
|
||||
}
|
||||
void DisplayManager::UpdateTopicData(const MsgId &id, const std::any &data) {
|
||||
UpdateDisplay(ToString(id), data);
|
||||
}
|
||||
void DisplayManager::slotSetRobotPose(const RobotPose &pose) {
|
||||
FactoryDisplay::Instance()->SetMoveEnable(DISPLAY_ROBOT, false);
|
||||
UpdateRobotPose(Eigen::Vector3f(pose.x, pose.y, pose.theta));
|
||||
UpdateRobotPose(pose);
|
||||
// enable move after 300ms
|
||||
QTimer::singleShot(300, [this]() {
|
||||
FactoryDisplay::Instance()->SetMoveEnable(DISPLAY_ROBOT, true);
|
||||
@ -62,7 +62,7 @@ void DisplayManager::slotSetNavPose(const RobotPose &pose) {
|
||||
FactoryDisplay::Instance()->SetMoveEnable(DISPLAY_GOAL, false);
|
||||
GetDisplay(DISPLAY_GOAL)
|
||||
->UpdateDisplay(
|
||||
wordPose2Map(Eigen::Vector3f(pose.x, pose.y, pose.theta)));
|
||||
wordPose2Map(pose));
|
||||
// enable move after 300ms
|
||||
QTimer::singleShot(300, [this]() {
|
||||
FactoryDisplay::Instance()->SetMoveEnable(DISPLAY_GOAL, true);
|
||||
@ -75,12 +75,12 @@ void DisplayManager::slotRobotScenePoseChanged(const RobotPose &pose) {
|
||||
double x, y;
|
||||
map_data_.occPose2xy(occ_pose.x(), occ_pose.y(), x, y);
|
||||
// 更新坐标
|
||||
robot_pose_[0] = x;
|
||||
robot_pose_[1] = y;
|
||||
robot_pose_[2] = pose.theta;
|
||||
robot_pose_.x = x;
|
||||
robot_pose_.y = y;
|
||||
robot_pose_.theta = pose.theta;
|
||||
|
||||
set_reloc_pose_widget_->SetPose(
|
||||
RobotPose(robot_pose_[0], robot_pose_[1], robot_pose_[2]));
|
||||
RobotPose(robot_pose_.x, robot_pose_.y, robot_pose_.theta));
|
||||
}
|
||||
}
|
||||
void DisplayManager::slotNavGoalScenePoseChanged(const RobotPose &pose) {
|
||||
@ -88,11 +88,11 @@ void DisplayManager::slotNavGoalScenePoseChanged(const RobotPose &pose) {
|
||||
GetDisplay(DISPLAY_MAP)->mapFromScene(QPointF(pose.x, pose.y));
|
||||
double x, y;
|
||||
map_data_.occPose2xy(occ_pose.x(), occ_pose.y(), x, y);
|
||||
robot_pose_goal_[0] = x;
|
||||
robot_pose_goal_[1] = y;
|
||||
robot_pose_goal_[2] = pose.theta;
|
||||
robot_pose_goal_.x = x;
|
||||
robot_pose_goal_.y = y;
|
||||
robot_pose_goal_.theta = pose.theta;
|
||||
set_nav_pose_widget_->SetPose(
|
||||
RobotPose(robot_pose_goal_[0], robot_pose_goal_[1], robot_pose_goal_[2]));
|
||||
RobotPose(robot_pose_goal_.x, robot_pose_goal_.y, robot_pose_goal_.theta));
|
||||
}
|
||||
void DisplayManager::InitUi() {
|
||||
set_reloc_pose_widget_ = new SetPoseWidget(graphics_view_ptr_);
|
||||
@ -164,79 +164,36 @@ bool DisplayManager::UpdateDisplay(const std::string &display_name,
|
||||
} else if (display_name == DISPLAY_ROBOT) {
|
||||
//重定位时屏蔽位置更新
|
||||
if (!is_reloc_mode_) {
|
||||
GetAnyData(Pose3f, data, robot_pose_);
|
||||
GetAnyData(RobotPose, data, robot_pose_);
|
||||
UpdateRobotPose(robot_pose_);
|
||||
}
|
||||
} else if (display_name == DISPLAY_LASER) {
|
||||
Display::LaserDataMap laser_data_map, laser_data_scene;
|
||||
GetAnyData(Display::LaserDataMap, data, laser_data_map)
|
||||
LaserScan laser_scan;
|
||||
GetAnyData(LaserScan, data, laser_scan)
|
||||
// 点坐标转换为图元坐标系下
|
||||
for (auto one_laser : laser_data_map) {
|
||||
laser_data_scene[one_laser.first] = transLaserPoint(one_laser.second);
|
||||
}
|
||||
|
||||
display->UpdateDisplay(laser_data_scene);
|
||||
} else if (display_name == DISPLAY_PARTICLE) {
|
||||
// 激光坐标转换为地图的图元坐标
|
||||
Display::ParticlePointsType particles;
|
||||
Display::ParticlePointsType particles_tans;
|
||||
GetAnyData(Display::ParticlePointsType, data, particles);
|
||||
for (auto one_points : particles) {
|
||||
// std::cout << "location:" << one_laser.first << std::endl;
|
||||
// 转换为图元坐标系
|
||||
double x, y;
|
||||
map_data_.xy2occPose(one_points[0], one_points[1], x, y);
|
||||
particles_tans.push_back(Eigen::Vector3f(x, y, one_points[2]));
|
||||
}
|
||||
display->UpdateDisplay(particles_tans);
|
||||
} else if (display_name == DISPLAY_GLOBAL_PATH ||
|
||||
laser_scan.data = transLaserPoint(laser_scan.data);
|
||||
|
||||
display->UpdateDisplay(laser_scan);
|
||||
}else if (display_name == DISPLAY_GLOBAL_PATH ||
|
||||
display_name == DISPLAY_LOCAL_PATH) {
|
||||
// 激光坐标转换为地图的图元坐标
|
||||
Display::PathData path_data;
|
||||
Display::PathData path_data_trans;
|
||||
GetAnyData(Display::PathData, data, path_data);
|
||||
RobotPath path_data;
|
||||
RobotPath path_data_trans;
|
||||
GetAnyData(RobotPath, data, path_data);
|
||||
for (auto one_points : path_data) {
|
||||
// std::cout << "location:" << one_laser.first << std::endl;
|
||||
// 转换为图元坐标系
|
||||
double x, y;
|
||||
map_data_.xy2occPose(one_points[0], one_points[1], x, y);
|
||||
path_data_trans.push_back(Display::Point2f(x, y));
|
||||
map_data_.xy2occPose(one_points.x, one_points.y, x, y);
|
||||
path_data_trans.push_back(Point(x, y));
|
||||
}
|
||||
display->UpdateDisplay(path_data_trans);
|
||||
} else if (display_name == DISPLAY_REGION) {
|
||||
Display::RegionDataMap region_data;
|
||||
Display::RegionDataMap region_tans;
|
||||
GetAnyData(Display::RegionDataMap, data, region_data);
|
||||
for (auto [region_name, region] : region_data) {
|
||||
std::vector<Display::RangeVec> range_ve;
|
||||
for (auto one_region : region) {
|
||||
Display::RangeVec ivec;
|
||||
double xmin, ymin, xmax, ymax;
|
||||
map_data_.xy2occPose(one_region[0], one_region[1], xmin, ymin);
|
||||
map_data_.xy2occPose(one_region[2], one_region[3], xmax, ymax);
|
||||
ivec[0] = xmin;
|
||||
ivec[1] = ymin;
|
||||
ivec[2] = xmax;
|
||||
ivec[3] = ymax;
|
||||
range_ve.push_back(ivec);
|
||||
}
|
||||
region_tans[region_name] = range_ve;
|
||||
}
|
||||
display->UpdateDisplay(region_tans);
|
||||
} else if (display_name == DISPLAY_LOCAL_COST_MAP) {
|
||||
if (data.type() == typeid(RobotPose)) {
|
||||
GetAnyData(RobotPose, data, local_cost_world_pose_);
|
||||
} else if (data.type() == typeid(CostMap)) {
|
||||
if (data.type() == typeid(CostMap)) {
|
||||
GetAnyData(CostMap, data, local_cost_map_);
|
||||
display->UpdateDisplay(data);
|
||||
} else {
|
||||
display->UpdateDisplay(data);
|
||||
}
|
||||
FactoryDisplay::Instance()->SetDisplayPoseInParent(
|
||||
DISPLAY_LOCAL_COST_MAP,
|
||||
wordPose2Map(Eigen::Vector3f(local_cost_world_pose_.x,
|
||||
local_cost_world_pose_.y,
|
||||
local_cost_world_pose_.theta)));
|
||||
} else {
|
||||
display->UpdateDisplay(data);
|
||||
}
|
||||
@ -246,19 +203,19 @@ bool DisplayManager::UpdateDisplay(const std::string &display_name,
|
||||
* @description:坐标系转换为图元坐标系
|
||||
* @return {*}
|
||||
*/
|
||||
std::vector<Eigen::Vector2f>
|
||||
DisplayManager::transLaserPoint(const std::vector<Eigen::Vector2f> &point) {
|
||||
std::vector<Point>
|
||||
DisplayManager::transLaserPoint(const std::vector<Point> &point) {
|
||||
// point为车身坐标系下的坐标 需要根据当前机器人坐标转换为map
|
||||
std::vector<Eigen::Vector2f> res;
|
||||
std::vector<Point> res;
|
||||
for (auto one_point : point) {
|
||||
//根据机器人坐标转换为map坐标系下
|
||||
basic::RobotPose map_pose = basic::absoluteSum(
|
||||
basic::RobotPose(robot_pose_[0], robot_pose_[1], robot_pose_[2]),
|
||||
basic::RobotPose(one_point[0], one_point[1], 0));
|
||||
basic::RobotPose(robot_pose_.x, robot_pose_.y, robot_pose_.theta),
|
||||
basic::RobotPose(one_point.x, one_point.y, 0));
|
||||
// 转换为图元坐标系
|
||||
double x, y;
|
||||
map_data_.xy2occPose(map_pose.x, map_pose.y, x, y);
|
||||
res.push_back(Eigen::Vector2f(x, y));
|
||||
res.push_back(Point(x, y));
|
||||
}
|
||||
return res;
|
||||
}
|
||||
@ -268,9 +225,8 @@ DisplayManager::transLaserPoint(const std::vector<Eigen::Vector2f> &point) {
|
||||
* @param {Vector3f&} pose x y theta
|
||||
* @return {*}
|
||||
*/
|
||||
void DisplayManager::UpdateRobotPose(const Eigen::Vector3f &pose) {
|
||||
void DisplayManager::UpdateRobotPose(const RobotPose &pose) {
|
||||
// FocusDisplay(DISPLAY_ROBOT);
|
||||
emit DisplayRobotPoseWorld(pose);
|
||||
robot_pose_ = pose;
|
||||
GetDisplay(DISPLAY_ROBOT)->UpdateDisplay(wordPose2Map(pose));
|
||||
}
|
||||
@ -282,7 +238,7 @@ void DisplayManager::SetRelocMode(bool is_start) {
|
||||
is_reloc_mode_ = is_start;
|
||||
if (is_start) {
|
||||
set_reloc_pose_widget_->SetPose(
|
||||
RobotPose(robot_pose_[0], robot_pose_[1], robot_pose_[2]));
|
||||
RobotPose(robot_pose_.x, robot_pose_.y, robot_pose_.theta));
|
||||
set_reloc_pose_widget_->show();
|
||||
} else {
|
||||
set_reloc_pose_widget_->hide();
|
||||
@ -309,19 +265,19 @@ void DisplayManager::FocusDisplay(const std::string &display_name) {
|
||||
* @param {Vector2f&} point 传入的点坐标
|
||||
* @return {*}
|
||||
*/
|
||||
Eigen::Vector3f DisplayManager::wordPose2Scene(const Eigen::Vector3f &point) {
|
||||
RobotPose DisplayManager::wordPose2Scene(const RobotPose &point) {
|
||||
// xy在栅格地图上的图元坐标
|
||||
double x, y;
|
||||
map_data_.xy2occPose(point[0], point[1], x, y);
|
||||
map_data_.xy2occPose(point.x, point.y, x, y);
|
||||
// xy在map图层上的坐标
|
||||
QPointF pose = FactoryDisplay::Instance()
|
||||
->GetDisplay(DISPLAY_MAP)
|
||||
->PoseToScene(QPointF(x, y));
|
||||
|
||||
Eigen::Vector3f res;
|
||||
res[0] = pose.x();
|
||||
res[1] = pose.y();
|
||||
res[2] = point[2];
|
||||
RobotPose res;
|
||||
res.x = pose.x();
|
||||
res.y = pose.y();
|
||||
res.theta = point.theta;
|
||||
return res;
|
||||
}
|
||||
/**
|
||||
@ -337,18 +293,12 @@ QPointF DisplayManager::wordPose2Scene(const QPointF &point) {
|
||||
->GetDisplay(DISPLAY_MAP)
|
||||
->PoseToScene(QPointF(x, y));
|
||||
}
|
||||
/**
|
||||
* @description: 世界坐标系点转为以map图层为栅格地图坐标系
|
||||
* @param {Vector2f&} point 传入的点坐标
|
||||
* @return {*}
|
||||
*/
|
||||
Eigen::Vector3f DisplayManager::wordPose2Map(const Eigen::Vector3f &pose) {
|
||||
Eigen::Vector3f ret;
|
||||
RobotPose DisplayManager::wordPose2Map(const RobotPose &pose) {
|
||||
RobotPose ret = pose;
|
||||
double x, y;
|
||||
map_data_.xy2occPose(pose[0], pose[1], x, y);
|
||||
ret[0] = x;
|
||||
ret[1] = y;
|
||||
ret[2] = pose[2];
|
||||
map_data_.xy2occPose(pose.x, pose.y, x, y);
|
||||
ret.x = x;
|
||||
ret.y = y;
|
||||
return ret;
|
||||
}
|
||||
QPointF DisplayManager::wordPose2Map(const QPointF &pose) {
|
||||
|
||||
@ -23,8 +23,8 @@ DisplayPath::~DisplayPath() {}
|
||||
bool DisplayPath::SetDisplayConfig(const std::string &config_name,
|
||||
const std::any &config_data) {
|
||||
if (config_name == "Color") {
|
||||
Display::Color color;
|
||||
GetAnyData(Display::Color, config_data, color);
|
||||
Color color;
|
||||
GetAnyData(Color, config_data, color);
|
||||
color_ = QColor(color[0], color[1], color[2]);
|
||||
} else {
|
||||
return false;
|
||||
@ -33,11 +33,11 @@ bool DisplayPath::SetDisplayConfig(const std::string &config_name,
|
||||
}
|
||||
bool DisplayPath::UpdateData(const std::any &data) {
|
||||
try {
|
||||
auto path_data = std::any_cast<Display::PathData>(data);
|
||||
auto path_data = std::any_cast<RobotPath>(data);
|
||||
computeBoundRect(path_data);
|
||||
path_points_.clear();
|
||||
for (auto one_path : path_data) {
|
||||
path_points_.push_back(QPointF(one_path[0], one_path[1]));
|
||||
path_points_.push_back(QPointF(one_path.x, one_path.y));
|
||||
}
|
||||
update();
|
||||
} catch (const std::bad_any_cast &e) {
|
||||
@ -52,18 +52,18 @@ void DisplayPath::drawPath(QPainter *painter) {
|
||||
// }
|
||||
painter->drawPoints(path_points_);
|
||||
}
|
||||
void DisplayPath::computeBoundRect(const Display::PathData &path) {
|
||||
void DisplayPath::computeBoundRect(const RobotPath &path) {
|
||||
if (path.empty())
|
||||
return;
|
||||
float xmax, xmin, ymax, ymin;
|
||||
|
||||
xmax = xmin = path[0][0];
|
||||
ymax = ymin = path[0][1];
|
||||
xmax = xmin = path[0].x;
|
||||
ymax = ymin = path[0].y;
|
||||
for (auto p : path) {
|
||||
xmax = xmax > p[0] ? xmax : p[0];
|
||||
xmin = xmin < p[0] ? xmin : p[0];
|
||||
ymax = ymax > p[1] ? ymax : p[1];
|
||||
ymin = ymin < p[1] ? ymin : p[1];
|
||||
xmax = xmax > p.x ? xmax : p.x;
|
||||
xmin = xmin < p.x ? xmin : p.x;
|
||||
ymax = ymax > p.y ? ymax : p.y;
|
||||
ymin = ymin < p.y ? ymin : p.y;
|
||||
}
|
||||
// std::cout << "xmax:" << xmax << "xmin:" << xmin << "ymax:" << ymax
|
||||
// << "ymin:" << ymin << std::endl;
|
||||
|
||||
@ -1,62 +0,0 @@
|
||||
/*
|
||||
* @Author: chengyang chengyangkj@outlook.com
|
||||
* @Date: 2023-04-10 15:38:40
|
||||
* @LastEditors: chengyangkj chengyangkj@qq.com
|
||||
* @LastEditTime: 2023-10-14 09:56:12
|
||||
* @FilePath: ////src/display/laser_points.cpp
|
||||
* @Description:
|
||||
*/
|
||||
#include "display/display_tag.h"
|
||||
namespace Display {
|
||||
DisplayTag::DisplayTag(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name)
|
||||
: VirtualDisplay(display_name, z_value, parent_name) {
|
||||
tag_image_.load("://images/qr.png");
|
||||
// enable_scale_ = false;
|
||||
}
|
||||
void DisplayTag::paint(QPainter *painter,
|
||||
const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget) {
|
||||
painter->setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing);
|
||||
for (auto [qr_name, pose] : tag_data_) {
|
||||
// std::cout << "paint qr_name:" << qr_name << std::endl;
|
||||
// 坐标转换为图元坐标系
|
||||
double x, y;
|
||||
map_data_.xy2occPose(pose[0], pose[1], x, y);
|
||||
painter->drawPixmap(x - tag_image_.width() / 2, y - tag_image_.height() / 2,
|
||||
tag_image_);
|
||||
}
|
||||
}
|
||||
|
||||
DisplayTag::~DisplayTag() {}
|
||||
bool DisplayTag::UpdateData(const std::any &data) {
|
||||
if (data.type() == typeid(Display::TagDataMap)) {
|
||||
tag_data_ = std::any_cast<Display::TagDataMap>(data);
|
||||
// std::cout << "update tag data size: " << tag_data_.size() << std::endl;
|
||||
computeBoundRect(tag_data_);
|
||||
update();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
void DisplayTag::computeBoundRect(Display::TagDataMap &data_map) {
|
||||
float xmax = -99999, xmin = 99999, ymax = -99999, ymin = 99999;
|
||||
// std::cout << "data map size:" << data_map.size() << std::endl;
|
||||
for (auto [region_name, pose] : data_map) {
|
||||
double x, y;
|
||||
map_data_.xy2occPose(pose[0], pose[1], x, y);
|
||||
if (xmin > x)
|
||||
xmin = x;
|
||||
if (xmax < x)
|
||||
xmax = x;
|
||||
|
||||
if (ymin > y)
|
||||
ymin = y;
|
||||
if (ymax < y)
|
||||
ymax = y;
|
||||
|
||||
// std::cout << "xmax:" << xmax << "xmin:" << xmin << "ymax:" << ymax
|
||||
// << "ymin:" << ymin <<" x:"<<x<<" y:"<<pose[1]<< std::endl;
|
||||
}
|
||||
SetBoundingRect(QRectF(xmin, ymin, xmax, ymax));
|
||||
}
|
||||
} // namespace Display
|
||||
@ -22,25 +22,27 @@ void LaserPoints::paint(QPainter *painter,
|
||||
LaserPoints::~LaserPoints() {}
|
||||
|
||||
bool LaserPoints::UpdateData(const std::any &data) {
|
||||
if (data.type() == typeid(Display::LaserDataMap)) {
|
||||
laser_data_scene_ = std::any_cast<Display::LaserDataMap>(data);
|
||||
if (data.type() == typeid(LaserScan)) {
|
||||
auto laser_scan = std::any_cast<LaserScan>(data);
|
||||
laser_data_scene_[laser_scan.id] = laser_scan.data;
|
||||
computeBoundRect(laser_data_scene_);
|
||||
}
|
||||
update();
|
||||
}
|
||||
void LaserPoints::computeBoundRect(const Display::LaserDataMap &laser_scan) {
|
||||
void LaserPoints::computeBoundRect(
|
||||
const std::map<int, std::vector<Point>> &laser_scan) {
|
||||
float xmax, xmin, ymax, ymin;
|
||||
for (auto [id, points] : laser_scan) {
|
||||
if (points.empty())
|
||||
continue;
|
||||
xmax = xmin = points[0][0];
|
||||
ymax = ymin = points[0][1];
|
||||
xmax = xmin = points[0].x;
|
||||
ymax = ymin = points[0].y;
|
||||
for (int i = 1; i < points.size(); ++i) {
|
||||
Eigen::Vector2f p = points[i];
|
||||
xmax = xmax > p[0] ? xmax : p[0];
|
||||
xmin = xmin < p[0] ? xmin : p[0];
|
||||
ymax = ymax > p[1] ? ymax : p[1];
|
||||
ymin = ymin < p[1] ? ymin : p[1];
|
||||
Point p = points[i];
|
||||
xmax = xmax > p.x ? xmax : p.x;
|
||||
xmin = xmin < p.x ? xmin : p.x;
|
||||
ymax = ymax > p.y ? ymax : p.y;
|
||||
ymin = ymin < p.y ? ymin : p.y;
|
||||
}
|
||||
}
|
||||
// std::cout << "xmax:" << xmax << "xmin:" << xmin << "ymax:" << ymax
|
||||
@ -49,19 +51,11 @@ void LaserPoints::computeBoundRect(const Display::LaserDataMap &laser_scan) {
|
||||
}
|
||||
bool LaserPoints::SetDisplayConfig(const std::string &config_name,
|
||||
const std::any &config_data) {
|
||||
if (config_name == "Color") {
|
||||
Display::LaserColorMap new_map;
|
||||
GetAnyData(Display::LaserColorMap, config_data, new_map);
|
||||
for (auto item : new_map) {
|
||||
location_to_color_[item.first] = item.second;
|
||||
}
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
void LaserPoints::drawLaser(QPainter *painter, int id,
|
||||
std::vector<Eigen::Vector2f> data) {
|
||||
std::vector<Point> data) {
|
||||
QColor color;
|
||||
if (!location_to_color_.count(id)) {
|
||||
int r, g, b;
|
||||
@ -72,7 +66,7 @@ void LaserPoints::drawLaser(QPainter *painter, int id,
|
||||
}
|
||||
painter->setPen(QPen(color));
|
||||
for (auto one_point : data) {
|
||||
QPointF point = QPointF(one_point[0], one_point[1]);
|
||||
QPointF point = QPointF(one_point.x, one_point.y);
|
||||
// std::cout<<"point:"<<point.x() <<" "<<point.y()<<std::endl;
|
||||
painter->drawPoint(point);
|
||||
}
|
||||
|
||||
@ -1,82 +0,0 @@
|
||||
/*
|
||||
* @Author: chengyang chengyangkj@outlook.com
|
||||
* @Date: 2023-04-10 15:38:40
|
||||
* @LastEditors: chengyang chengyangkj@outlook.com
|
||||
* @LastEditTime: 2023-04-24 13:46:43
|
||||
* @FilePath: ////src/display/laser_points.cpp
|
||||
* @Description:
|
||||
*/
|
||||
#include "display/particle_points.h"
|
||||
namespace Display {
|
||||
ParticlePoints::ParticlePoints(const std::string &display_name,
|
||||
const int &z_value, std::string parent_name)
|
||||
: VirtualDisplay(display_name, z_value, parent_name) {}
|
||||
void ParticlePoints::paint(QPainter *painter,
|
||||
const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget) {
|
||||
drawParticle(painter, particle_data_);
|
||||
}
|
||||
|
||||
ParticlePoints::~ParticlePoints() {}
|
||||
bool ParticlePoints::UpdateData(const std::any &data) {
|
||||
try {
|
||||
// particle_data_ 是地图图元坐标系下的坐标
|
||||
particle_data_ = std::any_cast<Display::ParticlePointsType>(data);
|
||||
computeBoundRect(particle_data_);
|
||||
update();
|
||||
} catch (const std::bad_any_cast &e) {
|
||||
std::cout << e.what() << '\n';
|
||||
}
|
||||
}
|
||||
void ParticlePoints::drawParticle(QPainter *painter,
|
||||
Display::ParticlePointsType particle) {
|
||||
for (auto one_point : particle) {
|
||||
QPen pen(QColor(0x0e, 0xbe, 0xff, 255), 1, Qt::SolidLine, Qt::RoundCap,
|
||||
Qt::RoundJoin);
|
||||
painter->setPen(pen);
|
||||
|
||||
double theta = -one_point[2];
|
||||
int length = 25; // 粒子的箭头长1m
|
||||
int x1 = one_point[0];
|
||||
int y1 = one_point[1];
|
||||
int x2 = x1 + cos(theta) * length;
|
||||
int y2 = y1 + sin(theta) * length;
|
||||
QPointF startPoint = QPointF(x1, y1);
|
||||
QPointF endPoint = QPointF(x2, y2);
|
||||
QLineF line(startPoint, endPoint);
|
||||
painter->drawLine(line);
|
||||
float angle =
|
||||
atan2(endPoint.y() - startPoint.y(), endPoint.x() - startPoint.x()) +
|
||||
3.1415926; //
|
||||
//绘制三角形
|
||||
QPolygonF points;
|
||||
points.push_back(endPoint);
|
||||
QPointF point1, point2;
|
||||
point1.setX(endPoint.x() + 10 * cos(angle - 0.5)); //求得箭头点1坐标
|
||||
point1.setY(endPoint.y() + 10 * sin(angle - 0.5));
|
||||
point2.setX(endPoint.x() + 10 * cos(angle + 0.5)); //求得箭头点2坐标
|
||||
point2.setY(endPoint.y() + 10 * sin(angle + 0.5));
|
||||
points.push_back(point1);
|
||||
points.push_back(point2);
|
||||
painter->drawPolygon(points);
|
||||
}
|
||||
}
|
||||
void ParticlePoints::computeBoundRect(
|
||||
const Display::ParticlePointsType &particle) {
|
||||
if (particle.empty())
|
||||
return;
|
||||
float xmax, xmin, ymax, ymin;
|
||||
|
||||
xmax = xmin = particle[0][0];
|
||||
ymax = ymin = particle[0][1];
|
||||
for (auto p : particle) {
|
||||
xmax = xmax > p[0] ? xmax : p[0];
|
||||
xmin = xmin < p[0] ? xmin : p[0];
|
||||
ymax = ymax > p[1] ? ymax : p[1];
|
||||
ymin = ymin < p[1] ? ymin : p[1];
|
||||
}
|
||||
// std::cout << "xmax:" << xmax << "xmin:" << xmin << "ymax:" << ymax
|
||||
// << "ymin:" << ymin << std::endl;
|
||||
SetBoundingRect(QRectF(xmin, ymin, xmax, ymax));
|
||||
}
|
||||
} // namespace Display
|
||||
@ -1,72 +0,0 @@
|
||||
/*
|
||||
* @Author: chengyang chengyangkj@outlook.com
|
||||
* @Date: 2023-04-10 15:38:40
|
||||
* @LastEditors: chengyangkj chengyangkj@qq.com
|
||||
* @LastEditTime: 2023-10-14 09:57:01
|
||||
* @FilePath: ////src/display/laser_points.cpp
|
||||
* @Description:
|
||||
*/
|
||||
#include "display/region.h"
|
||||
namespace Display {
|
||||
Region::Region(const std::string &display_name, const int &z_value,
|
||||
std::string parent_name)
|
||||
: VirtualDisplay(display_name, z_value, parent_name) {}
|
||||
void Region::paint(QPainter *painter, const QStyleOptionGraphicsItem *option,
|
||||
QWidget *widget) {
|
||||
for (auto [region_name, region] : region_data_) {
|
||||
// std::cout << "region name:" << region_name << std::endl;
|
||||
for (auto one_region : region) {
|
||||
// std::cout << "region:" << one_region[0] << " " << one_region[1] << " "
|
||||
// << one_region[2] << " " << one_region[3] << std::endl;
|
||||
QPen pen;
|
||||
pen.setColor(QColor(0, 255, 0, 70));
|
||||
QBrush brush;
|
||||
brush.setColor(QColor(0, 255, 0, 70));
|
||||
brush.setStyle(Qt::SolidPattern);
|
||||
painter->setPen(pen);
|
||||
painter->setBrush(brush);
|
||||
|
||||
painter->drawRect(QRectF(QPointF(one_region[0], one_region[1]),
|
||||
QPointF(one_region[2], one_region[3])));
|
||||
painter->setPen(Qt::blue);
|
||||
QFont font;
|
||||
|
||||
font.setCapitalization(QFont::SmallCaps);
|
||||
// 大小
|
||||
font.setPixelSize(bounding_rect_.height() / 50);
|
||||
painter->setFont(font);
|
||||
painter->drawText(QRectF(QPointF(one_region[0], one_region[1]),
|
||||
QPointF(one_region[2], one_region[3])),
|
||||
Qt::AlignCenter, QString::fromStdString(region_name));
|
||||
}
|
||||
}
|
||||
}
|
||||
void Region::computeBoundRect(Display::RegionDataMap &data_map) {
|
||||
float xmax = -99999, xmin = 99999, ymax = -99999, ymin = 99999;
|
||||
for (auto [region_name, region] : region_data_) {
|
||||
for (auto one_region : region) {
|
||||
if (xmin > one_region[0])
|
||||
xmin = one_region[0];
|
||||
if (xmax < one_region[1])
|
||||
xmax = one_region[1];
|
||||
|
||||
if (ymin > one_region[2])
|
||||
ymin = one_region[2];
|
||||
if (ymax < one_region[3])
|
||||
ymax = one_region[3];
|
||||
}
|
||||
// std::cout << "xmax:" << xmax << "xmin:" << xmin << "ymax:" << ymax
|
||||
// << "ymin:" << ymin << std::endl;
|
||||
SetBoundingRect(QRectF(xmin, ymin, xmax - xmin, ymax - ymin));
|
||||
}
|
||||
}
|
||||
Region::~Region() {}
|
||||
bool Region::UpdateData(const std::any &data) {
|
||||
if (data.type() == typeid(Display::RegionDataMap)) {
|
||||
region_data_ = std::any_cast<Display::RegionDataMap>(data);
|
||||
computeBoundRect(region_data_);
|
||||
update();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
} // namespace Display
|
||||
@ -3,7 +3,7 @@
|
||||
* @Date: 2023-10-06 07:12:50
|
||||
* @LastEditors: chengyangkj chengyangkj@qq.com
|
||||
* @LastEditTime: 2023-10-06 14:02:27
|
||||
* @FilePath: /ROS2_Qt5_Gui_App/src/ CMainWindow.cpp
|
||||
* @FilePath: /ROS2_Qt5_Gui_App/src/ MainWindow.cpp
|
||||
* @Description: 这是默认设置,请设置`customMade`, 打开koroFileHeader查看配置
|
||||
* 进行设置: https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
|
||||
*/
|
||||
@ -21,10 +21,9 @@
|
||||
#include "logger/easylogging++.h"
|
||||
|
||||
using namespace ads;
|
||||
|
||||
CMainWindow::CMainWindow(QWidget *parent)
|
||||
: QMainWindow(parent), ui(new Ui::CMainWindow) {
|
||||
LOG(INFO) << " CMainWindow init";
|
||||
MainWindow::MainWindow(QWidget *parent)
|
||||
: QMainWindow(parent), ui(new Ui::MainWindow) {
|
||||
LOG(INFO) << " MainWindow init";
|
||||
qRegisterMetaType<std::string>("std::string");
|
||||
qRegisterMetaType<RobotPose>("RobotPose");
|
||||
qRegisterMetaType<RobotSpeed>("RobotSpeed");
|
||||
@ -33,12 +32,44 @@ CMainWindow::CMainWindow(QWidget *parent)
|
||||
qRegisterMetaType<CostMap>("CostMap");
|
||||
qRegisterMetaType<LaserScan>("LaserScan");
|
||||
qRegisterMetaType<RobotPath>("RobotPath");
|
||||
qRegisterMetaType<MsgId>("MsgId");
|
||||
qRegisterMetaType<std::any>("std::any");
|
||||
setupUi();
|
||||
CommInstance::Instance()->start();
|
||||
}
|
||||
bool MainWindow::openChannel() {
|
||||
if (channel_manager_.OpenChannelAuto()) {
|
||||
registerChannel();
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
bool MainWindow::openChannel(const std::string &channel_name) {
|
||||
if (channel_manager_.OpenChannel(channel_name)) {
|
||||
registerChannel();
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
void MainWindow::registerChannel() {
|
||||
channel_manager_.RegisterOnDataCallback(
|
||||
std::move([=](const MsgId &id, const std::any &data) {
|
||||
switch (id) {
|
||||
case MsgId::kOdomPose:
|
||||
updateOdomInfo(std::any_cast<RobotState>(data));
|
||||
break;
|
||||
|
||||
CMainWindow::~CMainWindow() { delete ui; }
|
||||
void CMainWindow::setupUi() {
|
||||
default:
|
||||
break;
|
||||
}
|
||||
emit OnRecvChannelData(id, data);
|
||||
}));
|
||||
}
|
||||
void MainWindow::SendChannelMsg(const MsgId &id, const std::any &data) {
|
||||
channel_manager_.SendMessage(id, data);
|
||||
}
|
||||
void MainWindow::closeChannel() { channel_manager_.CloseChannel(); }
|
||||
MainWindow::~MainWindow() { delete ui; }
|
||||
void MainWindow::setupUi() {
|
||||
ui->setupUi(this);
|
||||
CDockManager::setConfigFlag(CDockManager::OpaqueSplitterResize, true);
|
||||
CDockManager::setConfigFlag(CDockManager::XmlCompressionEnabled, false);
|
||||
@ -124,7 +155,7 @@ void CMainWindow::setupUi() {
|
||||
speed_ctrl_widget_ = new SpeedCtrlWidget();
|
||||
connect(speed_ctrl_widget_, &SpeedCtrlWidget::signalControlSpeed,
|
||||
[this](const RobotSpeed &speed) {
|
||||
CommInstance::Instance()->PubRobotSpeed(speed);
|
||||
SendChannelMsg(MsgId::kSetRobotSpeed, speed);
|
||||
});
|
||||
ads::CDockWidget *SpeedCtrlDockWidget = new ads::CDockWidget("SpeedCtrl");
|
||||
SpeedCtrlDockWidget->setWidget(speed_ctrl_widget_);
|
||||
@ -135,38 +166,17 @@ void CMainWindow::setupUi() {
|
||||
|
||||
//////////////////////////////////////////////////////槽链接
|
||||
|
||||
connect(CommInstance::Instance(), SIGNAL(emitTopicData(QString)), this,
|
||||
SLOT(onRecvData(QString)));
|
||||
connect(CommInstance::Instance(), &VirtualChannelNode::emitUpdateMap,
|
||||
[this](OccupancyMap map) {
|
||||
display_manager_->UpdateDisplay(DISPLAY_MAP, map);
|
||||
connect(this, SIGNAL(OnRecvChannelData(const MsgId &, const std::any &)),
|
||||
display_manager_,
|
||||
SLOT(UpdateTopicData(const MsgId &, const std::any &)));
|
||||
connect(display_manager_, &Display::DisplayManager::signalPub2DPose,
|
||||
[this](const RobotPose &pose) {
|
||||
SendChannelMsg(MsgId::kSetNavGoalPose, pose);
|
||||
});
|
||||
connect(display_manager_, &Display::DisplayManager::signalPub2DGoal,
|
||||
[this](const RobotPose &pose) {
|
||||
SendChannelMsg(MsgId::kSetRelocPose, pose);
|
||||
});
|
||||
connect(CommInstance::Instance(),
|
||||
SIGNAL(emitUpdateLocalCostMap(CostMap, RobotPose)), this,
|
||||
SLOT(updateLocalCostMap(CostMap, RobotPose)));
|
||||
connect(CommInstance::Instance(), SIGNAL(emitUpdateGlobalCostMap(CostMap)),
|
||||
this, SLOT(updateGlobalCostMap(CostMap)));
|
||||
connect(CommInstance::Instance(), SIGNAL(emitUpdateRobotPose(RobotPose)),
|
||||
this, SLOT(slotUpdateRobotPose(RobotPose)));
|
||||
|
||||
connect(CommInstance::Instance(), SIGNAL(emitUpdateLaserPoint(LaserScan)),
|
||||
this, SLOT(slotUpdateLaserPoint(LaserScan)));
|
||||
connect(CommInstance::Instance(), SIGNAL(emitUpdatePath(RobotPath)), this,
|
||||
SLOT(updateGlobalPath(RobotPath)));
|
||||
connect(CommInstance::Instance(), SIGNAL(emitUpdateLocalPath(RobotPath)),
|
||||
this, SLOT(updateLocalPath(RobotPath)));
|
||||
connect(CommInstance::Instance(), SIGNAL(emitOdomInfo(RobotState)), this,
|
||||
SLOT(updateOdomInfo(RobotState)));
|
||||
// connect(m_roboItem, SIGNAL(signalRunMap(OccupancyMap)), m_roboGLWidget,
|
||||
// SLOT(updateRunMap(QPixmap)));
|
||||
// connect(CommInstance::Instance(),&rclcomm::emitUpdateMap,[this](QImage
|
||||
// img){
|
||||
// m_roboItem->updateMap(img);
|
||||
// });
|
||||
connect(display_manager_, SIGNAL(signalPub2DPose(const RobotPose &)),
|
||||
CommInstance::Instance(), SLOT(PubRelocPose(const RobotPose &)));
|
||||
connect(display_manager_, SIGNAL(signalPub2DGoal(const RobotPose &)),
|
||||
CommInstance::Instance(), SLOT(PubNavGoal(const RobotPose &)));
|
||||
// ui相关
|
||||
connect(tools_bar_widget_, &ToolsBarWidget::SignalSetRelocPose,
|
||||
[=]() { display_manager_->SetRelocPose(); });
|
||||
@ -177,15 +187,15 @@ void CMainWindow::setupUi() {
|
||||
SLOT(signalCursorPose(QPointF)));
|
||||
}
|
||||
|
||||
void CMainWindow::signalCursorPose(QPointF pos) {
|
||||
basic::Point mapPos = CommInstance::Instance()->transScenePoint2Word(
|
||||
basic::Point(pos.x(), pos.y()));
|
||||
label_pos_map_->setText("x: " + QString::number(mapPos.x).mid(0, 4) +
|
||||
" y: " + QString::number(mapPos.y).mid(0, 4));
|
||||
void MainWindow::signalCursorPose(QPointF pos) {
|
||||
// basic::Point mapPos = display_manager_->transScenePoint2Word(
|
||||
// basic::Point(pos.x(), pos.y()));
|
||||
// label_pos_map_->setText("x: " + QString::number(mapPos.x).mid(0, 4) +
|
||||
// " y: " + QString::number(mapPos.y).mid(0, 4));
|
||||
label_pos_scene_->setText("x: " + QString::number(pos.x()).mid(0, 4) +
|
||||
" y: " + QString::number(pos.y()).mid(0, 4));
|
||||
}
|
||||
void CMainWindow::savePerspective() {
|
||||
void MainWindow::savePerspective() {
|
||||
QString PerspectiveName =
|
||||
QInputDialog::getText(this, "Save Perspective", "Enter unique name:");
|
||||
if (PerspectiveName.isEmpty()) {
|
||||
@ -200,55 +210,13 @@ void CMainWindow::savePerspective() {
|
||||
}
|
||||
|
||||
//============================================================================
|
||||
void CMainWindow::closeEvent(QCloseEvent *event) {
|
||||
void MainWindow::closeEvent(QCloseEvent *event) {
|
||||
// Delete dock manager here to delete all floating widgets. This ensures
|
||||
// that all top level windows of the dock manager are properly closed
|
||||
dock_manager_->deleteLater();
|
||||
QMainWindow::closeEvent(event);
|
||||
}
|
||||
void CMainWindow::onRecvData(QString msg) {}
|
||||
void CMainWindow::updateLocalCostMap(CostMap map, basic::RobotPose pose) {
|
||||
display_manager_->UpdateDisplay(DISPLAY_LOCAL_COST_MAP, map);
|
||||
display_manager_->UpdateDisplay(DISPLAY_LOCAL_COST_MAP, pose);
|
||||
}
|
||||
void CMainWindow::updateGlobalCostMap(CostMap map) {
|
||||
display_manager_->UpdateDisplay(DISPLAY_GLOBAL_COST_MAP, map);
|
||||
}
|
||||
void CMainWindow::updateGlobalPath(RobotPath path) {
|
||||
Display::PathData data;
|
||||
for (auto one_point : path) {
|
||||
data.push_back(Display::Point2f(one_point.x, one_point.y));
|
||||
}
|
||||
display_manager_->UpdateDisplay(DISPLAY_GLOBAL_PATH, data);
|
||||
}
|
||||
void CMainWindow::updateLocalPath(RobotPath path) {
|
||||
Display::PathData data;
|
||||
for (auto one_point : path) {
|
||||
data.push_back(Display::Point2f(one_point.x, one_point.y));
|
||||
}
|
||||
display_manager_->UpdateDisplay(DISPLAY_LOCAL_PATH, data);
|
||||
}
|
||||
void CMainWindow::slotUpdateLaserPoint(LaserScan scan) {
|
||||
// 数据转换
|
||||
Display::LaserDataMap laser_data;
|
||||
|
||||
Display::LaserData vector_scan;
|
||||
for (auto one_point : scan.data) {
|
||||
Eigen::Vector2f point;
|
||||
point[0] = one_point.x;
|
||||
point[1] = one_point.y;
|
||||
vector_scan.push_back(point);
|
||||
}
|
||||
laser_data[scan.id] = vector_scan;
|
||||
|
||||
display_manager_->UpdateDisplay(DISPLAY_LASER, laser_data);
|
||||
}
|
||||
void CMainWindow::slotUpdateRobotPose(basic::RobotPose pose) {
|
||||
display_manager_->UpdateDisplay(DISPLAY_ROBOT,
|
||||
Display::Pose3f(pose.x, pose.y, pose.theta));
|
||||
}
|
||||
|
||||
void CMainWindow::updateOdomInfo(RobotState state) {
|
||||
void MainWindow::updateOdomInfo(RobotState state) {
|
||||
// 转向灯
|
||||
// if (state.w > 0.1) {
|
||||
// ui->label_turnLeft->setPixmap(
|
||||
|
||||
@ -1,7 +1,7 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>CMainWindow</class>
|
||||
<widget class="QMainWindow" name="CMainWindow">
|
||||
<class>MainWindow</class>
|
||||
<widget class="QMainWindow" name="MainWindow">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user