#include <scene_configurator.hpp>
Public Types | |
typedef boost::function< void(ISM::ObjectSetPtr)> | ProcessConfigurationFunction |
typedef boost::function< void(int)> | ProcessKeyboardInputFunction |
typedef boost::function< void(ISM::ObjectPtr)> | ProcessObjectInputFunction |
Public Member Functions | |
bool | getAutomaticProcessingActive () |
SceneConfigurator (ProcessConfigurationFunction processConfigFunc, ProcessKeyboardInputFunction processKeyboardInputFunc=ProcessKeyboardInputFunction(), ProcessObjectInputFunction processObjectInputFunc=ProcessObjectInputFunction()) | |
~SceneConfigurator () | |
Private Member Functions | |
void | automaticProcessingCallback (const ros::TimerEvent &e) |
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) |
bool | isCameraInMotion () |
void | keyboardInputMain (const unsigned int poll_rate) |
void | objectInputCallback (const asr_msgs::AsrObject &object) |
void | printEstimations () |
void | printHelpText () |
void | printStatus () |
void | processConfiguration () |
void | processKeyboardInput () |
void | updateVisualizationCallback (const ros::TimerEvent &e) |
Copyright (c) 2016, Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. SceneConfigurator class manages scene configurations and handles object & keyboard input.
Definition at line 43 of file scene_configurator.hpp.
typedef boost::function<void(ISM::ObjectSetPtr)> SceneConfigurator::ProcessConfigurationFunction |
Definition at line 46 of file scene_configurator.hpp.
typedef boost::function<void(int)> SceneConfigurator::ProcessKeyboardInputFunction |
Definition at line 47 of file scene_configurator.hpp.
typedef boost::function<void(ISM::ObjectPtr)> SceneConfigurator::ProcessObjectInputFunction |
Definition at line 48 of file scene_configurator.hpp.
SceneConfigurator::SceneConfigurator | ( | ProcessConfigurationFunction | processConfigFunc, |
ProcessKeyboardInputFunction | processKeyboardInputFunc = ProcessKeyboardInputFunction() , |
||
ProcessObjectInputFunction | processObjectInputFunc = ProcessObjectInputFunction() |
||
) |
SceneConfigurator constructor.
processConfigFunc | Function to process an object configuration. |
processKeyboardInputFunc | Function to process further keyboard commands. |
processObjectInputFunc | Function for further processing of incoming objects. |
Definition at line 46 of file scene_configurator.cpp.
SceneConfigurator::~SceneConfigurator | ( | ) |
Definition at line 114 of file scene_configurator.cpp.
|
private |
Callback for automatic processing of configurations.
e | Timer event with no meaning to us beyond its existence. |
Definition at line 295 of file scene_configurator.cpp.
bool SceneConfigurator::getAutomaticProcessingActive | ( | ) |
Definition at line 131 of file scene_configurator.cpp.
|
private |
Gets parameters from ROS Parameter Server.
object_topic | ROS topic on which object estimation messages are received. |
object_input_queue_size | Size of the ros::CallbackQueue for incoming object estimation messages. |
object_input_thread_count | Number of threads to process incoming object estimations. |
base_frame | Frame to which incoming object messages are transformed. |
ignore_types | Whether to use the type from AsrObject for converted ism object type. |
ignore_ids | Whether to use the id from AsrObject for converted ism object id. |
use_confidence_from_msg | Whether to use confidence from incoming object or use confidence 1.0. |
enable_rotation_mode | Whether incoming object orientations should be rotated to the rotation_frame (The rotation only takes place if baseFrame == rotationFrame.) or to an object. |
rotation_frame | |
rotation_object_type | |
rotation_object_id | |
enable_neighborhood_evaluation | Whether to use neightborhood evaluation or not. |
neighbour_angle_threshold | |
neighbour_distance_threshold | |
keyboard_poll_rate | |
visualization_topic | Where to publish visualization of scene configuration. |
Definition at line 451 of file scene_configurator.cpp.
|
private |
Check if the camera is in any kind of motion, e.g. the robot is moving.
Definition at line 267 of file scene_configurator.cpp.
|
private |
Main-Function of keyboard thread.
poll_rate | Rate (Hz) in which the keyboard will be polled for input. |
Definition at line 136 of file scene_configurator.cpp.
|
private |
Extract class and identifier (within class) from estimation given by object localization system. Object 6D pose is extracted as well and transformed into world coordinate frame fixed during app startup.
object | ROS object msgs from which information is extracted. |
Definition at line 236 of file scene_configurator.cpp.
|
private |
Definition at line 307 of file scene_configurator.cpp.
|
private |
Definition at line 337 of file scene_configurator.cpp.
|
private |
Definition at line 369 of file scene_configurator.cpp.
|
private |
Wrapper for the passed function processConfigFunc.
Definition at line 279 of file scene_configurator.cpp.
|
private |
Definition at line 155 of file scene_configurator.cpp.
|
private |
Callback to update visualization.
e | Timer event with no meaning to us beyond its existence. |
Definition at line 410 of file scene_configurator.cpp.
|
private |
Definition at line 82 of file scene_configurator.hpp.
|
private |
Definition at line 71 of file scene_configurator.hpp.
|
private |
Definition at line 70 of file scene_configurator.hpp.
|
private |
Definition at line 88 of file scene_configurator.hpp.
|
private |
Definition at line 85 of file scene_configurator.hpp.
|
private |
Definition at line 87 of file scene_configurator.hpp.
|
private |
Definition at line 67 of file scene_configurator.hpp.
|
private |
Definition at line 92 of file scene_configurator.hpp.
|
private |
Definition at line 98 of file scene_configurator.hpp.
|
private |
Definition at line 69 of file scene_configurator.hpp.
|
private |
Definition at line 91 of file scene_configurator.hpp.
|
private |
Definition at line 86 of file scene_configurator.hpp.
|
private |
Definition at line 74 of file scene_configurator.hpp.
|
private |
Definition at line 75 of file scene_configurator.hpp.
|
private |
Definition at line 76 of file scene_configurator.hpp.
|
private |
Definition at line 94 of file scene_configurator.hpp.
|
private |
Definition at line 93 of file scene_configurator.hpp.
|
private |
Definition at line 80 of file scene_configurator.hpp.
|
private |
Definition at line 97 of file scene_configurator.hpp.
|
private |
Definition at line 99 of file scene_configurator.hpp.