Skip to content

Commit

Permalink
used vtune to measure time taken to process a frame
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Jan 31, 2024
1 parent 4943275 commit de4459c
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 6 deletions.
2 changes: 2 additions & 0 deletions realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,8 @@ else()
set(link_libraries ${realsense2_LIBRARY})
endif()

list(APPEND link_libraries /opt/intel/oneapi/vtune/2024.0/sdk/lib64/libittnotify.a)

target_link_libraries(${PROJECT_NAME}
${link_libraries}
)
Expand Down
3 changes: 2 additions & 1 deletion realsense2_camera/include/named_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace realsense2_camera
class NamedFilter
{
public:
NamedFilter(std::shared_ptr<rs2::filter> filter, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled=false, bool is_set_parameters=true);
NamedFilter(std::shared_ptr<rs2::filter> filter, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, std::string name="Filter", bool is_enabled=false, bool is_set_parameters=true);
bool is_enabled() {return _is_enabled;};
rs2::frameset Process(rs2::frameset frameset);
rs2::frame Process(rs2::frame frame);
Expand All @@ -39,6 +39,7 @@ namespace realsense2_camera

public:
std::shared_ptr<rs2::filter> _filter;
std::string _name;

protected:
bool _is_enabled;
Expand Down
13 changes: 12 additions & 1 deletion realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
// Header files for disabling intra-process comms for static broadcaster.
#include <rclcpp/publisher_options.hpp>
#include <tf2_ros/qos.hpp>
#include "/opt/intel/oneapi/vtune/2024.0/sdk/include/ittnotify.h"

using namespace realsense2_camera;

Expand Down Expand Up @@ -247,7 +248,7 @@ void BaseRealSenseNode::setupFilters()
_filters.push_back(_colorizer_filter);
_filters.push_back(_pc_filter);

_align_depth_filter = std::make_shared<AlignDepthFilter>(std::make_shared<rs2::align>(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger);
_align_depth_filter = std::make_shared<AlignDepthFilter>(std::make_shared<rs2::gl::align>(RS2_STREAM_COLOR), update_align_depth_func, _parameters, _logger);
_filters.push_back(_align_depth_filter);
}

Expand Down Expand Up @@ -549,9 +550,19 @@ void BaseRealSenseNode::frame_callback(rs2::frame frame)
rs2::video_frame original_color_frame = frameset.get_color_frame();

ROS_DEBUG("num_filters: %d", static_cast<int>(_filters.size()));
__itt_domain* domain = __itt_domain_create("MyDomain");

for (auto filter_it : _filters)
{
char temp_name[15];
std::strcpy(temp_name, filter_it->_name.c_str());
//ROS_INFO_STREAM("filter naem: " << temp_name);
__itt_string_handle* task = __itt_string_handle_create(temp_name);
__itt_task_begin(domain, __itt_null, __itt_null, task);

frameset = filter_it->Process(frameset);

__itt_task_end(domain);
}

ROS_DEBUG("List of frameset after applying filters: size: %d", static_cast<int>(frameset.size()));
Expand Down
10 changes: 6 additions & 4 deletions realsense2_camera/src/named_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

using namespace realsense2_camera;

NamedFilter::NamedFilter(std::shared_ptr<rs2::filter> filter, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled, bool is_set_parameters):
_filter(filter), _is_enabled(is_enabled), _params(parameters, logger), _logger(logger)
NamedFilter::NamedFilter(std::shared_ptr<rs2::filter> filter, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, std::string name, bool is_enabled, bool is_set_parameters):
_filter(filter), _name(name), _is_enabled(is_enabled), _params(parameters, logger), _logger(logger)
{
if (is_set_parameters)
setParameters();
Expand Down Expand Up @@ -74,11 +74,12 @@ rs2::frame NamedFilter::Process(rs2::frame frame)


PointcloudFilter::PointcloudFilter(std::shared_ptr<rs2::filter> filter, rclcpp::Node& node, std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled):
NamedFilter(filter, parameters, logger, is_enabled, false),
NamedFilter(filter, parameters, logger, "pointcloud", is_enabled, false),
_node(node),
_allow_no_texture_points(ALLOW_NO_TEXTURE_POINTS),
_ordered_pc(ORDERED_PC)
{
//_name = "pointcloud";
setParameters();
}

Expand Down Expand Up @@ -292,8 +293,9 @@ void PointcloudFilter::Publish(rs2::points pc, const rclcpp::Time& t, const rs2:
AlignDepthFilter::AlignDepthFilter(std::shared_ptr<rs2::filter> filter,
std::function<void(const rclcpp::Parameter&)> update_align_depth_func,
std::shared_ptr<Parameters> parameters, rclcpp::Logger logger, bool is_enabled):
NamedFilter(filter, parameters, logger, is_enabled, false)
NamedFilter(filter, parameters, logger, "align_depth", is_enabled, false)
{
//_name = "align_depth";
_params.registerDynamicOptions(*(_filter.get()), "align_depth");
_params.getParameters()->setParamT("align_depth.enable", _is_enabled, update_align_depth_func);
_parameters_names.push_back("align_depth.enable");
Expand Down

0 comments on commit de4459c

Please sign in to comment.