@@ -42,7 +42,9 @@ class TestNode : public rclcpp ::Node
42
42
uint64_t g_receive_frame_count[2 ]; // only add this for test fps
43
43
bool dump_ = false ;
44
44
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 ;
46
48
};
47
49
48
50
// Constructor must be with parameter NodeOptions (component 's requirement)
@@ -51,7 +53,7 @@ TestNode::TestNode(const rclcpp::NodeOptions & options) : TestNode("test_node",
51
53
TestNode::TestNode (const std::string & name, const rclcpp::NodeOptions & options)
52
54
: rclcpp::Node(name, options)
53
55
{
54
- enable_depth = this ->declare_parameter (" subscirbe_depth" , false );
56
+ enable_depth_ = this ->declare_parameter (" subscirbe_depth" , false );
55
57
dump_ = this ->declare_parameter (" dump" , false );
56
58
dump_camera_info_ = this ->declare_parameter (" dump_camera_info" , false );
57
59
rclcpp::SubscriptionOptions sub_options;
@@ -63,7 +65,7 @@ TestNode::TestNode(const std::string & name, const rclcpp::NodeOptions & options
63
65
std::bind (&TestNode::handler_callback, this , std::placeholders::_1), sub_options);
64
66
camera_info_sub_ = this ->create_subscription <CAMERA_INFO_TOPIC_TYPE>(CAMERA_INFO_TOPIC_NAME, 10 ,
65
67
std::bind (&TestNode::camera_info_callback, this , std::placeholders::_1), sub_options);
66
- if (enable_depth ) {
68
+ if (enable_depth_ ) {
67
69
image_sub_ = this ->create_subscription <sensor_msgs::msg::Image>(" depth_image" , 10 ,
68
70
std::bind (&TestNode::image_callback, this , std::placeholders::_1), sub_options);
69
71
}
@@ -122,25 +124,19 @@ void TestNode::image_callback(const sensor_msgs::msg::Image::ConstSharedPtr & ha
122
124
123
125
this ->get_parameter (" dump" , dump_);
124
126
std::string name;
125
- int frame_id ;
127
+ depth_frame_id_++ ;
126
128
uint64_t timestamp = handler->header .stamp .sec * 1000000000ULL + handler->header .stamp .nanosec ;
127
129
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 );
135
131
if (dump_) {
136
132
int size = handler->height * handler->step ;
137
133
auto bufData = &handler->data [0 ];
138
134
char fname[256 ];
139
135
const char * prefix_name = " test" ;
140
136
std::string node_name = this ->get_name ();
141
137
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 ());
144
140
FILE * fd = fopen (fname, " wb" );
145
141
if (fd == NULL ) {
146
142
RCLCPP_ERROR (this ->get_logger (),
@@ -162,16 +158,10 @@ void TestNode::handler_callback(
162
158
163
159
this ->get_parameter (" dump" , dump_);
164
160
std::string name;
165
- int frame_id ;
161
+ handler_frame_id_++ ;
166
162
uint64_t timestamp = handler->header .stamp .sec * 1000000000ULL + handler->header .stamp .nanosec ;
167
163
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_);
175
165
if (dump_) {
176
166
std::shared_ptr<lib_mem_dmabuf::DmaBuffer> buffer = handler->dmabuf ;
177
167
buffer->map ();
@@ -182,8 +172,8 @@ void TestNode::handler_callback(
182
172
const char * prefix_name = " test" ;
183
173
std::string node_name = this ->get_name ();
184
174
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 ());
187
177
FILE * fd = fopen (fname, " wb" );
188
178
if (fd == NULL ) {
189
179
RCLCPP_ERROR (this ->get_logger (),
0 commit comments