Skip to content

Commit f2750ff

Browse files
committed
fix: fix the error frame_id in msg
Signed-off-by: Lin Zhanye <[email protected]>
1 parent a2c8afd commit f2750ff

File tree

7 files changed

+37
-29
lines changed

7 files changed

+37
-29
lines changed

CHANGELOG.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,12 @@
11
# Changelog for package qrb_ros_camera
22

3+
## 2.0.1 (2025-09-5)
4+
5+
- Fix msg frame_id error issue
6+
- Add OX03F10 camera config file
7+
- update document to support ubuntu as tier 1 platform
8+
- Contributors: Zhanye Lin, Peng Wang
9+
310
## 2.0.0 (2025-05-30)
411

512
- First version for jazzy

README.md

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -345,10 +345,20 @@ def generate_launch_description():
345345

346346
## 👨‍💻 Build from source
347347

348+
### Dependencies
348349
Install dependencies
349350

350351
```bash
351-
sudo apt install ros-jazzy-qrb-ros-transport-image-type
352+
sudo add-apt-repository ppa:ubuntu-qcom-iot/qcom-noble-ppa
353+
sudo add-apt-repository ppa:ubuntu-qcom-iot/qirp
354+
sudo apt update
355+
356+
sudo apt install ros-jazzy-qrb-ros-transport-image-type \
357+
ros-dev-tools \
358+
qcom-camera-server \
359+
qcom-syslog-plumber-dev \
360+
libqmmf-dev \
361+
qcom-camxapi-dev
352362
```
353363

354364
Download the source code and build with colcon

qrb_camera/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
cmake_minimum_required(VERSION 3.8.2)
2-
project(qrb_camera VERSION 2.0.0)
2+
project(qrb_camera VERSION 2.0.1)
33

44
set(CMAKE_INCLUDE_CURRENT_DIR ON)
55

@@ -51,4 +51,4 @@ if(BUILD_TESTING)
5151

5252
endif()
5353

54-
ament_auto_package()
54+
ament_auto_package()

qrb_camera/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>qrb_camera</name>
5-
<version>2.0.0</version>
5+
<version>2.0.1</version>
66
<description>Qualcomm Robotics Camera Interface</description>
77
<maintainer email="[email protected]">Zhanye Lin</maintainer>
88
<license>BSD-3-Clause-Clear</license>

qrb_ros_camera/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>qrb_ros_camera</name>
5-
<version>2.0.0</version>
5+
<version>2.0.1</version>
66
<description>camera ros2node</description>
77
<maintainer email="[email protected]">Tian Ding</maintainer>
88
<license>BSD-3-Clause-Clear</license>

qrb_ros_camera/src/camera_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -163,7 +163,8 @@ std::unique_ptr<qrb_ros::transport::type::Image> CameraNode::convert_camera_fram
163163
auto timestamp = frame->timestamp + time_offset_;
164164
image_handler->header.stamp.sec = timestamp / 1000000000LL;
165165
image_handler->header.stamp.nanosec = timestamp % 1000000000LL;
166-
image_handler->header.frame_id = frame->stream_name + "_" + std::to_string(frame->frame_id);
166+
image_handler->header.frame_id =
167+
"cam" + std::to_string(configure_->get_camera_param().camera_id) + "_" + frame->stream_name;
167168
image_handler->width = frame->width;
168169
image_handler->height = frame->height;
169170
image_handler->encoding = frame->format;

qrb_ros_camera/test/src/camera_test.cpp

Lines changed: 13 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,9 @@ class TestNode : public rclcpp ::Node
4242
uint64_t g_receive_frame_count[2]; // only add this for test fps
4343
bool dump_ = false;
4444
bool dump_camera_info_ = false;
45-
bool enable_depth = false;
45+
bool enable_depth_ = false;
46+
int handler_frame_id_ = 0;
47+
int depth_frame_id_ = 0;
4648
};
4749

4850
// Constructor must be with parameter NodeOptions (component 's requirement)
@@ -51,7 +53,7 @@ TestNode::TestNode(const rclcpp::NodeOptions & options) : TestNode("test_node",
5153
TestNode::TestNode(const std::string & name, const rclcpp::NodeOptions & options)
5254
: rclcpp::Node(name, options)
5355
{
54-
enable_depth = this->declare_parameter("subscirbe_depth", false);
56+
enable_depth_ = this->declare_parameter("subscirbe_depth", false);
5557
dump_ = this->declare_parameter("dump", false);
5658
dump_camera_info_ = this->declare_parameter("dump_camera_info", false);
5759
rclcpp::SubscriptionOptions sub_options;
@@ -63,7 +65,7 @@ TestNode::TestNode(const std::string & name, const rclcpp::NodeOptions & options
6365
std::bind(&TestNode::handler_callback, this, std::placeholders::_1), sub_options);
6466
camera_info_sub_ = this->create_subscription<CAMERA_INFO_TOPIC_TYPE>(CAMERA_INFO_TOPIC_NAME, 10,
6567
std::bind(&TestNode::camera_info_callback, this, std::placeholders::_1), sub_options);
66-
if (enable_depth) {
68+
if (enable_depth_) {
6769
image_sub_ = this->create_subscription<sensor_msgs::msg::Image>("depth_image", 10,
6870
std::bind(&TestNode::image_callback, this, std::placeholders::_1), sub_options);
6971
}
@@ -122,25 +124,19 @@ void TestNode::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & ha
122124

123125
this->get_parameter("dump", dump_);
124126
std::string name;
125-
int frame_id;
127+
depth_frame_id_++;
126128
uint64_t timestamp = handler->header.stamp.sec * 1000000000ULL + handler->header.stamp.nanosec;
127129

128-
size_t pos = handler->header.frame_id.find('_');
129-
if (pos != std::string::npos) {
130-
name = handler->header.frame_id.substr(0, pos);
131-
frame_id = std::stoi(handler->header.frame_id.substr(pos + 1));
132-
}
133-
134-
show_fps(name, handler->encoding, timestamp, handler->height, handler->width, frame_id, 1);
130+
show_fps(name, handler->encoding, timestamp, handler->height, handler->width, depth_frame_id_, 1);
135131
if (dump_) {
136132
int size = handler->height * handler->step;
137133
auto bufData = &handler->data[0];
138134
char fname[256];
139135
const char * prefix_name = "test";
140136
std::string node_name = this->get_name();
141137
snprintf(fname, sizeof(fname), "%s/%s-%s_wh[%dx%d]_%s-%d-%s.raw", CAMERAROS2_WORKDIR,
142-
prefix_name, node_name.c_str(), handler->width, handler->height, name.c_str(), frame_id,
143-
handler->encoding.c_str());
138+
prefix_name, node_name.c_str(), handler->width, handler->height, name.c_str(),
139+
depth_frame_id_, handler->encoding.c_str());
144140
FILE * fd = fopen(fname, "wb");
145141
if (fd == NULL) {
146142
RCLCPP_ERROR(this->get_logger(),
@@ -162,16 +158,10 @@ void TestNode::handler_callback(
162158

163159
this->get_parameter("dump", dump_);
164160
std::string name;
165-
int frame_id;
161+
handler_frame_id_++;
166162
uint64_t timestamp = handler->header.stamp.sec * 1000000000ULL + handler->header.stamp.nanosec;
167163

168-
size_t pos = handler->header.frame_id.find('_');
169-
if (pos != std::string::npos) {
170-
name = handler->header.frame_id.substr(0, pos);
171-
frame_id = std::stoi(handler->header.frame_id.substr(pos + 1));
172-
}
173-
174-
show_fps(name, handler->encoding, timestamp, handler->height, handler->width, frame_id);
164+
show_fps(name, handler->encoding, timestamp, handler->height, handler->width, handler_frame_id_);
175165
if (dump_) {
176166
std::shared_ptr<lib_mem_dmabuf::DmaBuffer> buffer = handler->dmabuf;
177167
buffer->map();
@@ -182,8 +172,8 @@ void TestNode::handler_callback(
182172
const char * prefix_name = "test";
183173
std::string node_name = this->get_name();
184174
snprintf(fname, sizeof(fname), "%s/%s-%s_wh[%dx%d]_%s-%d.%s", CAMERAROS2_WORKDIR, prefix_name,
185-
node_name.c_str(), handler->width, handler->height, name.c_str(), frame_id,
186-
handler->encoding.c_str());
175+
node_name.c_str(), handler->width, handler->height, name.c_str(),
176+
handler_frame_id_, handler->encoding.c_str());
187177
FILE * fd = fopen(fname, "wb");
188178
if (fd == NULL) {
189179
RCLCPP_ERROR(this->get_logger(),

0 commit comments

Comments
 (0)