Skip to content

Commit 7214bd7

Browse files
committed
Cpp support for marker visual loc
1 parent d0e26b7 commit 7214bd7

19 files changed

Lines changed: 937 additions & 0 deletions

File tree

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
cmake_minimum_required(VERSION 3.10)
2+
project(VisualMarkerLibs CXX)
3+
4+
set(CMAKE_CXX_STANDARD 17)
5+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
6+
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
7+
8+
find_package(ament_cmake REQUIRED)
9+
10+
set(ROS2_PACKAGES
11+
rclcpp
12+
nav_msgs
13+
gazebo_msgs
14+
geometry_msgs
15+
sensor_msgs
16+
std_msgs
17+
tf2
18+
tf2_geometry_msgs
19+
ros_gz_interfaces
20+
cv_bridge
21+
)
22+
23+
foreach(pkg IN LISTS ROS2_PACKAGES)
24+
find_package(${pkg} REQUIRED)
25+
endforeach()
26+
27+
find_package(Boost REQUIRED COMPONENTS system)
28+
find_package(nlohmann_json REQUIRED)
29+
find_package(OpenCV REQUIRED)
30+
31+
set(COMMON_INTERFACES_INCLUDE "/home/ws/install/common_interfaces_cpp/include")
32+
set(COMMON_INTERFACES_LIB "/home/ws/install/common_interfaces_cpp/lib/libcommon_interfaces_cpp.so")
33+
34+
set(WEBGUI_ROS_DEPS rclcpp nav_msgs gazebo_msgs tf2 tf2_geometry_msgs sensor_msgs cv_bridge)
35+
set(WEBGUI_SYS_DEPS Frequency Boost::system nlohmann_json::nlohmann_json ${OpenCV_LIBRARIES} ${COMMON_INTERFACES_LIB})
36+
set(HAL_ROS_DEPS rclcpp geometry_msgs sensor_msgs std_msgs ros_gz_interfaces nav_msgs cv_bridge)
37+
set(HAL_SYS_DEPS ${OpenCV_LIBRARIES} ${COMMON_INTERFACES_LIB})
38+
39+
# --- libFrequency.so ---
40+
add_library(Frequency SHARED src/Frequency.cpp)
41+
target_include_directories(Frequency PUBLIC include)
42+
43+
# --- libWebGUI.so ---
44+
add_library(WebGUI SHARED src/WebGUI.cpp src/Map.cpp)
45+
target_include_directories(WebGUI PUBLIC include ${OpenCV_INCLUDE_DIRS} ${COMMON_INTERFACES_INCLUDE})
46+
47+
ament_target_dependencies(WebGUI ${WEBGUI_ROS_DEPS})
48+
target_link_libraries(WebGUI ${WEBGUI_SYS_DEPS})
49+
50+
# --- libHAL.so ---
51+
add_library(HAL SHARED src/HAL.cpp)
52+
target_include_directories(HAL PUBLIC include ${COMMON_INTERFACES_INCLUDE})
53+
54+
ament_target_dependencies(HAL ${HAL_ROS_DEPS})
55+
target_link_libraries(HAL ${HAL_SYS_DEPS})
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
#ifndef INCLUDE_FREQUENCY_HPP_
2+
#define INCLUDE_FREQUENCY_HPP_
3+
4+
#include <chrono>
5+
#include <cmath>
6+
#include <thread>
7+
8+
class Frequency
9+
{
10+
private:
11+
std::chrono::high_resolution_clock::time_point last_time;
12+
int is_first_iteration;
13+
14+
public:
15+
Frequency();
16+
~Frequency();
17+
18+
static int rate;
19+
void tick(int ideal_cycle = 50);
20+
};
21+
22+
#endif
Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
#ifndef HAL_HPP_
2+
#define HAL_HPP_
3+
4+
#include <memory>
5+
#include <thread>
6+
#include <vector>
7+
#include <string>
8+
#include <opencv2/opencv.hpp>
9+
10+
#include "rclcpp/rclcpp.hpp"
11+
#include "common_interfaces_cpp/hal/motors.hpp"
12+
#include "common_interfaces_cpp/hal/odometry.hpp"
13+
#include "common_interfaces_cpp/hal/laser.hpp"
14+
#include "common_interfaces_cpp/hal/camera.hpp"
15+
16+
class HAL : public rclcpp::Node {
17+
public:
18+
HAL();
19+
20+
static Pose3d getPose3d();
21+
static Pose3d getOdom();
22+
static cv::Mat getImage();
23+
static LaserData getLaserData();
24+
25+
static void setV(float v);
26+
static void setW(float w);
27+
28+
private:
29+
static std::shared_ptr<MotorsNode> motor_node_;
30+
static std::shared_ptr<CameraNode> camera_node_;
31+
static std::shared_ptr<OdometryNode> odometry_node_;
32+
static std::shared_ptr<LaserNode> laser_node_;
33+
static std::shared_ptr<OdometryNode> noisy_odometry_node_;
34+
35+
std::thread spin_thread_;
36+
};
37+
38+
#endif
Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
#ifndef INCLUDE_MAP_HPP_
2+
#define INCLUDE_MAP_HPP_
3+
4+
#include <vector>
5+
#include <functional>
6+
#include <cmath>
7+
#include "common_interfaces_cpp/hal/odometry.hpp"
8+
9+
class Map
10+
{
11+
public:
12+
Map(std::function<Pose3d()> pose_getter, std::function<Pose3d()> noisy_pose_getter);
13+
14+
std::vector<std::vector<double>> RTx(double angle, double tx, double ty, double tz);
15+
std::vector<std::vector<double>> RTy(double angle, double tx, double ty, double tz);
16+
std::vector<std::vector<double>> RTz(double angle, double tx, double ty, double tz);
17+
std::vector<std::vector<double>> RTVacuum();
18+
19+
std::vector<double> getRobotCoordinates();
20+
std::vector<double> getRobotCoordinatesWithNoise();
21+
22+
void reset();
23+
24+
private:
25+
std::function<Pose3d()> pose_getter_;
26+
std::function<Pose3d()> noisy_pose_getter_;
27+
};
28+
29+
#endif
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
#ifndef WEBGUI_HPP_
2+
#define WEBGUI_HPP_
3+
4+
#include <string>
5+
#include <memory>
6+
#include <thread>
7+
#include <mutex>
8+
#include <tuple>
9+
#include <vector>
10+
#include <functional>
11+
#include <nlohmann/json.hpp>
12+
#include <opencv2/opencv.hpp>
13+
#include "rclcpp/rclcpp.hpp"
14+
#include "geometry_msgs/msg/pose_stamped.hpp"
15+
#include "common_interfaces_cpp/webgui/MeasuringThreadingGUI.hpp"
16+
#include "Map.hpp"
17+
#include "common_interfaces_cpp/hal/odometry.hpp"
18+
#include "common_interfaces_cpp/hal/camera.hpp"
19+
20+
std::string base64_encode(unsigned char const* bytes_to_encode, unsigned int in_len);
21+
22+
class WebGUI : public MeasuringThreadingGUI {
23+
public:
24+
WebGUI(const std::string& host = "127.0.0.1", const std::string& port = "2303", double freq = 30.0);
25+
~WebGUI() override;
26+
27+
static void showImage(const cv::Mat& image);
28+
static void showEstimatedPose(const std::tuple<double, double, double>& pose);
29+
30+
void setImage(const cv::Mat& image);
31+
void setEstimatedRobotPose(const std::tuple<double, double, double>& pose);
32+
33+
Pose3d get_pose3d();
34+
Pose3d get_odom();
35+
36+
protected:
37+
void update_gui() override;
38+
39+
private:
40+
void setup_ros2();
41+
void estimated_pose_callback(const geometry_msgs::msg::PoseStamped::SharedPtr msg);
42+
43+
cv::Mat image_;
44+
std::mutex image_lock_;
45+
46+
std::tuple<double, double, double> predict_pose_;
47+
bool has_predict_pose_;
48+
49+
std::shared_ptr<rclcpp::Node> bridge_node_;
50+
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr estimated_pose_sub_;
51+
52+
std::shared_ptr<OdometryNode> real_odom_node_;
53+
std::shared_ptr<OdometryNode> noisy_odom_node_;
54+
std::shared_ptr<CameraNode> camera_node_;
55+
56+
std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;
57+
std::thread executor_thread_;
58+
59+
std::shared_ptr<Map> map_;
60+
};
61+
62+
extern std::shared_ptr<WebGUI> gui;
63+
64+
#endif
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
#include "Frequency.hpp"
2+
3+
int Frequency::rate = 0;
4+
5+
Frequency::Frequency() : is_first_iteration(1) {}
6+
7+
Frequency::~Frequency() {}
8+
9+
void Frequency::tick(int ideal_cycle)
10+
{
11+
const auto ideal_ms = std::chrono::milliseconds(1000 / ideal_cycle);
12+
const auto now = std::chrono::high_resolution_clock::now();
13+
14+
if (is_first_iteration == 1)
15+
{
16+
last_time = now;
17+
is_first_iteration = 0;
18+
return;
19+
}
20+
21+
const auto iter_ms = std::chrono::duration_cast<std::chrono::milliseconds>(now - last_time);
22+
23+
if (iter_ms < ideal_ms)
24+
{
25+
rate = std::round(1000.0 / ideal_ms.count());
26+
std::this_thread::sleep_for(ideal_ms - iter_ms);
27+
}
28+
else
29+
{
30+
rate = std::round(1000.0 / iter_ms.count());
31+
}
32+
33+
last_time = now;
34+
}
Lines changed: 86 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
#include "HAL.hpp"
2+
3+
using namespace std::chrono_literals;
4+
5+
std::shared_ptr<MotorsNode> HAL::motor_node_ = nullptr;
6+
std::shared_ptr<CameraNode> HAL::camera_node_ = nullptr;
7+
std::shared_ptr<OdometryNode> HAL::odometry_node_ = nullptr;
8+
std::shared_ptr<LaserNode> HAL::laser_node_ = nullptr;
9+
std::shared_ptr<OdometryNode> HAL::noisy_odometry_node_ = nullptr;
10+
11+
HAL::HAL() : Node("hal_node")
12+
{
13+
motor_node_ = std::make_shared<MotorsNode>("/turtlebot3/cmd_vel", 4.0, 0.3);
14+
camera_node_ = std::make_shared<CameraNode>("/turtlebot3/camera/image_raw");
15+
odometry_node_ = std::make_shared<OdometryNode>("/turtlebot3/odom");
16+
laser_node_ = std::make_shared<LaserNode>("/turtlebot3/laser/scan");
17+
noisy_odometry_node_ = std::make_shared<OdometryNode>("/turtlebot3/odom_noisy", "noisy_odometry_node");
18+
19+
spin_thread_ = std::thread([]() {
20+
rclcpp::executors::MultiThreadedExecutor executor;
21+
executor.add_node(camera_node_);
22+
executor.add_node(odometry_node_);
23+
executor.add_node(laser_node_);
24+
executor.add_node(noisy_odometry_node_);
25+
26+
while (rclcpp::ok()) {
27+
executor.spin_some();
28+
std::this_thread::sleep_for(11ms);
29+
}
30+
});
31+
spin_thread_.detach();
32+
}
33+
34+
Pose3d HAL::getPose3d()
35+
{
36+
if (odometry_node_) {
37+
return odometry_node_->getPose3d();
38+
}
39+
return Pose3d();
40+
}
41+
42+
Pose3d HAL::getOdom()
43+
{
44+
if (noisy_odometry_node_) {
45+
return noisy_odometry_node_->getPose3d();
46+
}
47+
return Pose3d();
48+
}
49+
50+
cv::Mat HAL::getImage()
51+
{
52+
std::shared_ptr<Image> img = nullptr;
53+
while (img == nullptr && rclcpp::ok()) {
54+
img = camera_node_->getImage();
55+
if (img == nullptr) {
56+
std::this_thread::sleep_for(10ms);
57+
}
58+
}
59+
return img->data;
60+
}
61+
62+
LaserData HAL::getLaserData()
63+
{
64+
LaserData laser_data = laser_node_->getLaserData();
65+
while (laser_data.values.empty() && rclcpp::ok()) {
66+
laser_data = laser_node_->getLaserData();
67+
if (laser_data.values.empty()) {
68+
std::this_thread::sleep_for(10ms);
69+
}
70+
}
71+
return laser_data;
72+
}
73+
74+
void HAL::setV(float v)
75+
{
76+
if (motor_node_) {
77+
motor_node_->sendV(static_cast<double>(v));
78+
}
79+
}
80+
81+
void HAL::setW(float w)
82+
{
83+
if (motor_node_) {
84+
motor_node_->sendW(static_cast<double>(w));
85+
}
86+
}

0 commit comments

Comments
 (0)