adi_3dtof_image_stitching.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c), 2023 - Analog Devices Inc. All Rights Reserved.
3 This software is PROPRIETARY & CONFIDENTIAL to Analog Devices, Inc.
4 and its licensors.
5 ******************************************************************************/
7 #include <ros/ros.h>
8 #include <boost/thread/thread.hpp>
9 
17 int main(int argc, char** argv)
18 {
19  ros::init(argc, argv, "adi_adtf31xx_sensor_stitch");
20 
21  // initialize function profiling
23 
24  // Create an instance of ADI3DToFImageStitching
25  ADI3DToFImageStitching adi_3dtof_image_stitching;
26 
27  bool thread_spawn_status = true;
28  // Spawn the process output thread..
29  // Note: It does nothing till the processing is triggered
30  boost::thread process_output_thread;
31  try
32  {
33  process_output_thread = boost::thread(&ADI3DToFImageStitching::processOutput, &adi_3dtof_image_stitching);
34  }
35  catch (const std::exception& e)
36  {
37  thread_spawn_status = false;
38  std::cerr << "Exception when trying to spawn process_output_thread : " << e.what() << '\n';
39  }
40 
41  ros::Rate loop_rate(100);
42 
43  while ((ros::ok()) && (thread_spawn_status))
44  {
51  if (!adi_3dtof_image_stitching.stitchFrames())
52  {
53  adi_3dtof_image_stitching.shutDownAllNodes();
54  }
55 
57 
58  loop_rate.sleep();
59 
60  ros::spinOnce();
61  }
62 
63  // closing profiling
65 
66  // Flag error
67  adi_3dtof_image_stitching.inputReadAbort();
68  if (thread_spawn_status)
69  {
70  // Signal thread abort
71  adi_3dtof_image_stitching.processOutputAbort();
72  try
73  {
74  // Wait for the thread to complete
75  process_output_thread.join();
76  }
77  catch (const std::exception& e)
78  {
79  std::cerr << " Exception in process_output_thread.join() : " << e.what() << '\n';
80  }
81  }
82 
83  ros::shutdown();
84 
85  return 0;
86 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ADI3DToFImageStitching::inputReadAbort
void inputReadAbort()
Definition: adi_3dtof_image_stitching.h:417
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::shutdown
ROSCPP_DECL void shutdown()
ADI3DToFImageStitching
This is main class for this package.
Definition: adi_3dtof_image_stitching.h:97
ros::ok
ROSCPP_DECL bool ok()
ADI3DToFImageStitching::processOutput
void processOutput()
The output process function, this is running a loop which reads the frame from the putput queue,...
Definition: adi_3dtof_image_stitching_output_thread.cpp:65
INIT_FUNCTION_PROFILE
#define INIT_FUNCTION_PROFILE()
Definition: module_profile.h:28
ADI3DToFImageStitching::processOutputAbort
void processOutputAbort()
This function sets the abort flag for the output thread, the function is normally called by the main ...
Definition: adi_3dtof_image_stitching_output_thread.cpp:18
FLUSH_FUNCTION_PROFILE
#define FLUSH_FUNCTION_PROFILE()
Definition: module_profile.h:27
main
int main(int argc, char **argv)
This is main function.
Definition: adi_3dtof_image_stitching.cpp:17
ros::Rate::sleep
bool sleep()
CLOSE_FUNCTION_PROFILE
#define CLOSE_FUNCTION_PROFILE()
Definition: module_profile.h:29
ADI3DToFImageStitching::shutDownAllNodes
void shutDownAllNodes()
This function shuts down all the nodes running in a roscore.
Definition: adi_3dtof_image_stitching.h:290
ADI3DToFImageStitching::stitchFrames
bool stitchFrames()
Stitch function.
Definition: stitch_frames.cpp:30
ros::Rate
adi_3dtof_image_stitching.h


adi_3dtof_image_stitching
Author(s):
autogenerated on Fri Mar 21 2025 02:27:20