Skip to content

Commit 1ab3d58

Browse files
authored
Merge pull request #3275 from JdeRobot/continue-cpp-webgui
Finish cpp webgui
2 parents f958be0 + 167ad5f commit 1ab3d58

File tree

14 files changed

+25882
-315
lines changed

14 files changed

+25882
-315
lines changed

exercises/static/exercises/follow_line/cpp_template/ros2_humble/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,19 +9,23 @@ find_package(ament_cmake REQUIRED)
99
find_package(rclcpp REQUIRED)
1010
find_package(geometry_msgs REQUIRED)
1111
find_package(std_msgs REQUIRED)
12+
find_package(nav_msgs REQUIRED)
1213
find_package(cv_bridge REQUIRED)
1314
find_package(OpenCV REQUIRED)
1415
find_package(image_transport REQUIRED)
1516
find_package(message_filters REQUIRED)
1617
find_package(sensor_msgs REQUIRED)
18+
find_package(gazebo_msgs REQUIRED)
1719

1820
set(dependencies
1921
rclcpp
2022
cv_bridge
2123
sensor_msgs
24+
nav_msgs
2225
OpenCV
2326
geometry_msgs
2427
std_msgs
28+
gazebo_msgs
2529
image_transport
2630
message_filters
2731
)

exercises/static/exercises/follow_line/cpp_template/ros2_humble/Frequency.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
#include <chrono>
55
#include <iostream>
66
#include <thread>
7+
#include <bits/stdc++.h>
78

89
using namespace std;
910

@@ -17,6 +18,7 @@ class Frequency
1718
Frequency(/* args */);
1819
~Frequency();
1920

21+
static int rate;
2022
void tick(int ideal_cycle);
2123
};
2224

@@ -45,11 +47,18 @@ void Frequency::tick(int ideal_cycle = 50)
4547

4648
if (iter_ms < ideal_ms)
4749
{
50+
rate = round(1000 / ideal_ms.count());
4851
this_thread::sleep_for(chrono::milliseconds(ideal_ms - iter_ms));
4952
}
53+
else
54+
{
55+
rate = round(1000 / iter_ms.count());
56+
}
5057

5158
last_time = now;
5259
return;
5360
}
5461

62+
int Frequency::rate = 0;
63+
5564
#endif

exercises/static/exercises/follow_line/cpp_template/ros2_humble/HAL.hpp

Lines changed: 36 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,9 @@
22
#define INCLUDE_HAL_HPP_
33

44
#include "geometry_msgs/msg/twist.hpp"
5+
#include "gazebo_msgs/msg/performance_metrics.hpp"
56
#include "sensor_msgs/msg/image.hpp"
7+
#include "nav_msgs/msg/odometry.hpp"
68
#include "rclcpp/rclcpp.hpp"
79
#include "cv_bridge/cv_bridge.h"
810
#include "opencv2/opencv.hpp"
@@ -18,8 +20,14 @@ class HAL : public rclcpp::Node
1820
{
1921
vel_pub_ = create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
2022
cam_sub_ = create_subscription<sensor_msgs::msg::Image>(
21-
"/cam_f1_left/image_raw", 1,
23+
"/cam_f1_left/image_raw", 10,
2224
std::bind(&HAL::topic_callback_info, this, _1));
25+
odom_sub_ = create_subscription<nav_msgs::msg::Odometry>(
26+
"/odom", 10,
27+
std::bind(&HAL::pose_callback, this, _1));
28+
perf_sub_ = create_subscription<gazebo_msgs::msg::PerformanceMetrics>(
29+
"/performance_metrics", 10,
30+
std::bind(&HAL::performance_callback, this, _1));
2331
};
2432

2533
static void set_v(const float speed)
@@ -39,10 +47,20 @@ class HAL : public rclcpp::Node
3947
return image_rgb;
4048
};
4149

50+
static vector<double> get_pose()
51+
{
52+
vector<double> v = {last_odom.pose.pose.position.x, last_odom.pose.pose.position.y, last_odom.pose.pose.position.z};
53+
return v;
54+
};
55+
56+
static double get_performance()
57+
{
58+
return last_perf.real_time_factor;
59+
};
60+
4261
private:
4362
void topic_callback_info(sensor_msgs::msg::Image::UniquePtr msg)
4463
{
45-
cout << "Image received" << endl;
4664
// Convert ROS Image to OpenCV Image | sensor_msgs::msg::Image -> cv::Mat
4765
cv_bridge::CvImagePtr image_rgb_ptr;
4866
try
@@ -58,17 +76,33 @@ class HAL : public rclcpp::Node
5876
image_rgb = image_rgb_raw;
5977
};
6078

79+
void pose_callback(nav_msgs::msg::Odometry::UniquePtr msg)
80+
{
81+
last_odom = *msg;
82+
};
83+
84+
void performance_callback(gazebo_msgs::msg::PerformanceMetrics::UniquePtr msg)
85+
{
86+
last_perf = *msg;
87+
};
88+
6189
// Publisher
6290
static rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr vel_pub_;
6391
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr cam_sub_;
92+
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
93+
rclcpp::Subscription<gazebo_msgs::msg::PerformanceMetrics>::SharedPtr perf_sub_;
6494

6595
// Message
6696
static geometry_msgs::msg::Twist last_twist;
6797
static cv::Mat image_rgb;
98+
static nav_msgs::msg::Odometry last_odom;
99+
static gazebo_msgs::msg::PerformanceMetrics last_perf;
68100
};
69101

70102
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr HAL::vel_pub_ = nullptr;
71103
geometry_msgs::msg::Twist HAL::last_twist = geometry_msgs::msg::Twist();
104+
nav_msgs::msg::Odometry HAL::last_odom = nav_msgs::msg::Odometry();
105+
gazebo_msgs::msg::PerformanceMetrics HAL::last_perf = gazebo_msgs::msg::PerformanceMetrics();
72106
cv::Mat HAL::image_rgb = cv::Mat();
73107

74108
#endif
Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
#ifndef INCLUDE_LAP_HPP_
2+
#define INCLUDE_LAP_HPP_
3+
4+
#include <chrono>
5+
#include <iostream>
6+
#include <thread>
7+
#include <string>
8+
#include "HAL.hpp"
9+
#include <stdio.h>
10+
11+
using namespace std;
12+
13+
class Lap
14+
{
15+
private:
16+
chrono::milliseconds lap_time;
17+
chrono::_V2::system_clock::time_point start_time;
18+
19+
bool paused = false;
20+
21+
public:
22+
Lap();
23+
~Lap();
24+
25+
void pause();
26+
void start();
27+
void reset();
28+
std::string getLapTime();
29+
};
30+
31+
Lap::Lap()
32+
{
33+
this->reset();
34+
}
35+
36+
Lap::~Lap()
37+
{
38+
}
39+
40+
std::string Lap::getLapTime()
41+
{
42+
if (!paused)
43+
{
44+
lap_time += chrono::duration_cast<chrono::milliseconds>(chrono::high_resolution_clock::now() - start_time);
45+
start_time = chrono::high_resolution_clock::now();
46+
}
47+
48+
char buff[70];
49+
const int sec = lap_time.count() / 1000;
50+
const int min = sec / 60;
51+
const int h = min / 60;
52+
sprintf(buff, "%d:%d:%d.%ld",h, min, sec, lap_time.count() % 1000);
53+
return std::string(buff);
54+
}
55+
56+
void Lap::reset()
57+
{
58+
start_time = chrono::high_resolution_clock::now();
59+
lap_time = chrono::milliseconds(0);
60+
paused = false;
61+
return;
62+
}
63+
64+
void Lap::pause()
65+
{
66+
paused = true;
67+
return;
68+
}
69+
70+
void Lap::start()
71+
{
72+
start_time = chrono::high_resolution_clock::now();
73+
paused = false;
74+
return;
75+
}
76+
77+
#endif

0 commit comments

Comments
 (0)