Skip to content

Commit 4a5bb43

Browse files
authored
Merge pull request #3772 from aquintan4/cpp-global-nav
C++ Global Navigation
2 parents fcedf7d + f26c7ca commit 4a5bb43

20 files changed

Lines changed: 997 additions & 1 deletion

File tree

database/exercises/db.sql

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ COPY public.exercises (id, exercise_id, name, description, tags, status, url) FR
116116
3 autoparking Autoparking Autoparking exercise testing ["AUTONOMOUS DRIVING","SERVICE ROBOTS","ROS2"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/autoparking
117117
4 follow_person Follow Person Follow a person with kobuki robot ["ROS2"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/follow_person
118118
5 vacuum_cleaner_loc Localized Vacuum Cleaner Localiized vauum clenaer ["ROS2", "MOBILE ROBOTS", "SERVICE ROBOTS"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/MobileRobots/vacuum_cleaner_loc
119-
6 global_navigation Global Navigation Global navigation exercise using REACT and RAM ["ROS2"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/global_navigation
119+
6 global_navigation Global Navigation Global navigation exercise using REACT and RAM ["ROS2", "MULTILANGUAGE"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/global_navigation
120120
7 rescue_people Drone Rescue People Drone Rescue People exercise ["ROS2"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/Drones/rescue_people
121121
8 obstacle_avoidance Obstacle Avoidance Obstacle Avoidance exercise using React and RAM ["ROS2","AUTONOMOUS DRIVING", "MULTILANGUAGE"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/AutonomousCars/obstacle_avoidance
122122
9 3d_reconstruction 3D Reconstruction 3D Reconstruction exercise using React and RAM ["ROS2","COMPUTER VISION"] ACTIVE https://jderobot.github.io/RoboticsAcademy/exercises/ComputerVision/3d_reconstruction
Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,54 @@
1+
cmake_minimum_required(VERSION 3.10)
2+
project(GlobalNavigationLibs 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+
geometry_msgs
14+
sensor_msgs
15+
cv_bridge
16+
)
17+
18+
foreach(pkg IN LISTS ROS2_PACKAGES)
19+
find_package(${pkg} REQUIRED)
20+
endforeach()
21+
22+
find_package(Boost REQUIRED COMPONENTS system)
23+
find_package(nlohmann_json REQUIRED)
24+
find_package(OpenCV REQUIRED)
25+
26+
set(COMMON_INTERFACES_INCLUDE "/home/ws/install/common_interfaces_cpp/include")
27+
set(COMMON_INTERFACES_LIB "/home/ws/install/common_interfaces_cpp/lib/libcommon_interfaces_cpp.so")
28+
29+
set(HAL_ROS_DEPS rclcpp geometry_msgs nav_msgs)
30+
set(WEBGUI_ROS_DEPS rclcpp nav_msgs geometry_msgs sensor_msgs cv_bridge)
31+
set(WEBGUI_SYS_DEPS Frequency Boost::system nlohmann_json::nlohmann_json ${OpenCV_LIBS})
32+
33+
34+
# --- libFrequency.so ---
35+
add_library(Frequency SHARED src/Frequency.cpp)
36+
target_include_directories(Frequency PUBLIC include)
37+
38+
# --- libHAL.so ---
39+
add_library(HAL SHARED src/HAL.cpp)
40+
target_include_directories(HAL PUBLIC include ${COMMON_INTERFACES_INCLUDE})
41+
42+
ament_target_dependencies(HAL ${HAL_ROS_DEPS})
43+
target_link_libraries(HAL ${COMMON_INTERFACES_LIB})
44+
45+
# --- libWebGUI.so ---
46+
add_library(WebGUI SHARED src/WebGUI.cpp src/Map.cpp)
47+
target_include_directories(WebGUI PUBLIC
48+
include
49+
${COMMON_INTERFACES_INCLUDE}
50+
${OpenCV_INCLUDE_DIRS}
51+
)
52+
53+
ament_target_dependencies(WebGUI ${WEBGUI_ROS_DEPS})
54+
target_link_libraries(WebGUI ${WEBGUI_SYS_DEPS} ${COMMON_INTERFACES_LIB})
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: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
#ifndef INCLUDE_HAL_HPP_
2+
#define INCLUDE_HAL_HPP_
3+
4+
#include <memory>
5+
#include <thread>
6+
#include <chrono>
7+
#include "rclcpp/rclcpp.hpp"
8+
#include "common_interfaces_cpp/hal/motors.hpp"
9+
#include "common_interfaces_cpp/hal/odometry.hpp"
10+
11+
class HAL : public rclcpp::Node
12+
{
13+
public:
14+
HAL();
15+
static void set_v(const float speed);
16+
static void set_w(const float speed);
17+
static Pose3d get_pose3d();
18+
19+
private:
20+
static std::shared_ptr<MotorsNode> motors_node_;
21+
static std::shared_ptr<OdometryNode> odometry_node_;
22+
std::thread spin_thread_;
23+
};
24+
25+
#endif
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
#ifndef INCLUDE_MAP_HPP_
2+
#define INCLUDE_MAP_HPP_
3+
4+
#include <vector>
5+
#include <string>
6+
#include <functional>
7+
#include <opencv2/opencv.hpp>
8+
#include "common_interfaces_cpp/hal/odometry.hpp"
9+
10+
class Map
11+
{
12+
public:
13+
Map(std::function<Pose3d()> pose_cb);
14+
15+
cv::Mat RTx(double angle, double tx, double ty, double tz);
16+
cv::Mat RTy(double angle, double tx, double ty, double tz);
17+
cv::Mat RTz(double angle, double tx, double ty, double tz);
18+
19+
cv::Mat RTWorldGrid();
20+
cv::Mat RTGridWorld();
21+
cv::Mat RTFormula();
22+
23+
std::vector<int> worldToGrid(double worldX, double worldY);
24+
std::vector<double> gridToWorld(int gridX, int gridY);
25+
26+
double getGridVal(int x, int y);
27+
void setGridVal(int x, int y, double val);
28+
29+
std::vector<int> getTaxiCoordinates();
30+
std::vector<double> getTaxiAngle();
31+
32+
std::vector<int> rowColumn(const std::vector<double>& pose);
33+
34+
void reset();
35+
void robotPose();
36+
37+
cv::Mat getMap(const std::string& url);
38+
39+
int worldWidth;
40+
int worldHeight;
41+
int gridWidth;
42+
int gridHeight;
43+
44+
private:
45+
std::function<Pose3d()> pose_callback_;
46+
cv::Mat grid_;
47+
};
48+
49+
#endif
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
#ifndef INCLUDE_WEBGUI_HPP_
2+
#define INCLUDE_WEBGUI_HPP_
3+
4+
#include <boost/beast/core.hpp>
5+
#include <boost/beast/websocket.hpp>
6+
#include <boost/asio/connect.hpp>
7+
#include <boost/asio/ip/tcp.hpp>
8+
#include <boost/asio/strand.hpp>
9+
#include <nlohmann/json.hpp>
10+
#include <opencv2/opencv.hpp>
11+
#include <mutex>
12+
#include <memory>
13+
#include <string>
14+
#include <vector>
15+
#include "rclcpp/rclcpp.hpp"
16+
#include "geometry_msgs/msg/point.hpp"
17+
#include "nav_msgs/msg/path.hpp"
18+
#include "sensor_msgs/msg/image.hpp"
19+
#include "common_interfaces_cpp/hal/odometry.hpp"
20+
#include "Map.hpp"
21+
22+
namespace beast = boost::beast;
23+
namespace websocket = beast::websocket;
24+
namespace net = boost::asio;
25+
using tcp = net::ip::tcp;
26+
using json = nlohmann::json;
27+
28+
class WebGUI
29+
{
30+
public:
31+
WebGUI();
32+
33+
static void showNumpy(const cv::Mat& image);
34+
static void showPath(const std::vector<std::vector<int>>& array);
35+
static std::vector<double> getTargetPose();
36+
static cv::Mat getMap(const std::string& url);
37+
static std::vector<int> rowColumn(const std::vector<double>& pose);
38+
static std::vector<int> worldToGrid(const std::vector<double>& pose);
39+
static std::vector<double> gridToWorld(const std::vector<int>& cell);
40+
static void reset_gui();
41+
static std::string payloadImage();
42+
43+
static std::vector<double> worldXY;
44+
static std::string array_str;
45+
46+
private:
47+
static cv::Mat image_to_be_shown;
48+
static bool image_to_be_shown_updated;
49+
static std::mutex image_show_lock;
50+
static std::mutex array_lock;
51+
};
52+
53+
class WebGUINode : public rclcpp::Node
54+
{
55+
public:
56+
WebGUINode();
57+
58+
static std::shared_ptr<Map> map_;
59+
static std::shared_ptr<OdometryNode> pose3d_node_;
60+
61+
static void publish_target(double x, double y);
62+
63+
private:
64+
void path_callback(nav_msgs::msg::Path::UniquePtr msg);
65+
void image_callback(sensor_msgs::msg::Image::UniquePtr msg);
66+
67+
rclcpp::Subscription<nav_msgs::msg::Path>::SharedPtr path_sub_;
68+
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
69+
70+
static std::shared_ptr<rclcpp::Publisher<geometry_msgs::msg::Point>> target_pub_;
71+
};
72+
73+
#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: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
#include "HAL.hpp"
2+
3+
using namespace std::chrono_literals;
4+
5+
std::shared_ptr<MotorsNode> HAL::motors_node_ = nullptr;
6+
std::shared_ptr<OdometryNode> HAL::odometry_node_ = nullptr;
7+
8+
HAL::HAL() : Node("hal_node")
9+
{
10+
motors_node_ = std::make_shared<MotorsNode>("/cmd_vel", 4.0, 0.3);
11+
odometry_node_ = std::make_shared<OdometryNode>("/odom", "hal_odometry_node");
12+
13+
spin_thread_ = std::thread([]() {
14+
rclcpp::executors::SingleThreadedExecutor executor;
15+
executor.add_node(HAL::motors_node_);
16+
executor.add_node(HAL::odometry_node_);
17+
18+
while (rclcpp::ok()) {
19+
executor.spin_some();
20+
std::this_thread::sleep_for(std::chrono::milliseconds(10));
21+
}
22+
});
23+
spin_thread_.detach();
24+
}
25+
26+
void HAL::set_v(const float speed)
27+
{
28+
if (motors_node_) {
29+
motors_node_->sendV(static_cast<double>(speed));
30+
}
31+
}
32+
33+
void HAL::set_w(const float speed)
34+
{
35+
if (motors_node_) {
36+
motors_node_->sendW(static_cast<double>(speed));
37+
}
38+
}
39+
40+
Pose3d HAL::get_pose3d()
41+
{
42+
if (odometry_node_) {
43+
return odometry_node_->getPose3d();
44+
}
45+
return Pose3d();
46+
}

0 commit comments

Comments
 (0)