scene_configurator.hpp
Go to the documentation of this file.
1 
18 #pragma once
19 
20 // Local Includes
22 #include "../ism_helper.hpp"
23 
24 // Global Includes
25 #include <string>
26 #include <boost/shared_ptr.hpp>
27 #include <boost/thread.hpp>
28 
29 #include <termios.h> //Keyboard Input: termios, TCSANOW, ECHO, ICANON
30 
31 // Pkg Includes
32 #include "ros/ros.h"
33 #include <asr_ism_visualizations/ObjectModelVisualizerRVIZ.hpp>
34 #include <asr_msgs/AsrObject.h>
35 
36 // ISM Inlcude
37 #include <ISM/common_type/Object.hpp>
38 
39 
44 {
45  public:
46  typedef boost::function<void(ISM::ObjectSetPtr)> ProcessConfigurationFunction;
47  typedef boost::function<void(int)> ProcessKeyboardInputFunction;
48  typedef boost::function<void(ISM::ObjectPtr)> ProcessObjectInputFunction;
49 
50 
58  SceneConfigurator(ProcessConfigurationFunction processConfigFunc, ProcessKeyboardInputFunction processKeyboardInputFunc = ProcessKeyboardInputFunction(), ProcessObjectInputFunction processObjectInputFunc = ProcessObjectInputFunction());
60 
65 
66  private:
68 
72 
73  /*** Functions provided from other objects ***/
74  ProcessConfigurationFunction processConfigurationFunc_;
75  ProcessKeyboardInputFunction processKeyboardInputFunc_;
76  ProcessObjectInputFunction processObjectInputFunc_;
77 
78  /*** States ***/
79  //Whether only marked objects or marked objects and any additional object in the current view are used for scene processing.
81  //Whether to process the scene automatically.
83 
84  /*** Keyboard Input ***/
85  boost::thread *keyboard_thread_;
89 
90  /*** Object Input ***/
95 
96  /*** Visualization ***/
98  VIZ::ObjectModelVisualizerRVIZ* object_model_visualizer_;
100 
101 
102 
108  void keyboardInputMain(const unsigned int poll_rate);
109  void processKeyboardInput();
110 
111 
117  void objectInputCallback(const asr_msgs::AsrObject& object);
118 
122  bool isCameraInMotion();
123 
127  void processConfiguration();
128 
135 
136  /* Print Information on CLI */
137  void printEstimations();
138  void printHelpText();
139  void printStatus();
140 
147 
168  void getNodeParameters(std::string& object_topic, int& queue_size, int& object_input_thread_count, std::string& base_frame, bool& ignore_types, bool& ignore_ids, bool& use_confidence_from_msg,
169  int& enable_rotation_mode, std::string& rotation_frame, std::string& rotation_object_type, std::string& rotation_object_id,
170  bool& enable_neighborhood_evaluation, double& neighbour_angle_threshold, double& neighbour_distance_threshold,
171  int& keyboard_poll_rate, double& automatic_processing_interval, std::string& visualization_topic);
172 };
ProcessKeyboardInputFunction processKeyboardInputFunc_
SceneConfigurator(ProcessConfigurationFunction processConfigFunc, ProcessKeyboardInputFunction processKeyboardInputFunc=ProcessKeyboardInputFunction(), ProcessObjectInputFunction processObjectInputFunc=ProcessObjectInputFunction())
void objectInputCallback(const asr_msgs::AsrObject &object)
void keyboardInputMain(const unsigned int poll_rate)
boost::function< void(ISM::ObjectSetPtr)> ProcessConfigurationFunction
void updateVisualizationCallback(const ros::TimerEvent &e)
boost::function< void(int)> ProcessKeyboardInputFunction
void automaticProcessingCallback(const ros::TimerEvent &e)
ros::CallbackQueue object_queue_
boost::function< void(ISM::ObjectPtr)> ProcessObjectInputFunction
void getNodeParameters(std::string &object_topic, int &queue_size, int &object_input_thread_count, std::string &base_frame, bool &ignore_types, bool &ignore_ids, bool &use_confidence_from_msg, int &enable_rotation_mode, std::string &rotation_frame, std::string &rotation_object_type, std::string &rotation_object_id, bool &enable_neighborhood_evaluation, double &neighbour_angle_threshold, double &neighbour_distance_threshold, int &keyboard_poll_rate, double &automatic_processing_interval, std::string &visualization_topic)
ProcessObjectInputFunction processObjectInputFunc_
ros::AsyncSpinner * spinner_
ros::Timer visualization_timer_
boost::thread * keyboard_thread_
ros::Publisher visualization_publisher_
VIZ::ObjectModelVisualizerRVIZ * object_model_visualizer_
IH::ObjectConverterPtr object_msg_converter_
ros::Subscriber object_input_subscriber_
ProcessConfigurationFunction processConfigurationFunc_
ros::Timer automatic_processing_timer_
SceneConfiguratorData * data_
ros::NodeHandlePtr ptu_


asr_ism
Author(s): Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Thu Jan 9 2020 07:20:58