Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
SceneConfigurator Class Reference

#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)
 

Private Attributes

bool automatic_processing_active_
 
ros::Timer automatic_processing_timer_
 
SceneConfiguratorDatadata_
 
bool key_pressed_
 
boost::thread * keyboard_thread_
 
termios modified_terminal_settings_
 
ros::NodeHandle nh_
 
ros::Subscriber object_input_subscriber_
 
VIZ::ObjectModelVisualizerRVIZ * object_model_visualizer_
 
IH::ObjectConverterPtr object_msg_converter_
 
ros::CallbackQueue object_queue_
 
termios original_terminal_settings_
 
ProcessConfigurationFunction processConfigurationFunc_
 
ProcessKeyboardInputFunction processKeyboardInputFunc_
 
ProcessObjectInputFunction processObjectInputFunc_
 
ros::NodeHandlePtr ptu_
 
ros::AsyncSpinnerspinner_
 
bool use_only_marked_objects_
 
ros::Publisher visualization_publisher_
 
ros::Timer visualization_timer_
 

Detailed Description

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:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
  3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

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.

Member Typedef Documentation

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.

Constructor & Destructor Documentation

SceneConfigurator::SceneConfigurator ( ProcessConfigurationFunction  processConfigFunc,
ProcessKeyboardInputFunction  processKeyboardInputFunc = ProcessKeyboardInputFunction(),
ProcessObjectInputFunction  processObjectInputFunc = ProcessObjectInputFunction() 
)

SceneConfigurator constructor.

Parameters
processConfigFuncFunction to process an object configuration.
processKeyboardInputFuncFunction to process further keyboard commands.
processObjectInputFuncFunction 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.

Member Function Documentation

void SceneConfigurator::automaticProcessingCallback ( const ros::TimerEvent e)
private

Callback for automatic processing of configurations.

Parameters
eTimer event with no meaning to us beyond its existence.

Definition at line 295 of file scene_configurator.cpp.

bool SceneConfigurator::getAutomaticProcessingActive ( )
Returns
if object configurations are processed automatically in a certain time interval.

Definition at line 131 of file scene_configurator.cpp.

void SceneConfigurator::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 
)
private

Gets parameters from ROS Parameter Server.

Parameters
object_topicROS topic on which object estimation messages are received.
object_input_queue_sizeSize of the ros::CallbackQueue for incoming object estimation messages.
object_input_thread_countNumber of threads to process incoming object estimations.
base_frameFrame to which incoming object messages are transformed.
ignore_typesWhether to use the type from AsrObject for converted ism object type.
ignore_idsWhether to use the id from AsrObject for converted ism object id.
use_confidence_from_msgWhether to use confidence from incoming object or use confidence 1.0.
enable_rotation_modeWhether 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_evaluationWhether to use neightborhood evaluation or not.
neighbour_angle_threshold
neighbour_distance_threshold
keyboard_poll_rate
visualization_topicWhere to publish visualization of scene configuration.

Definition at line 451 of file scene_configurator.cpp.

bool SceneConfigurator::isCameraInMotion ( )
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.

void SceneConfigurator::keyboardInputMain ( const unsigned int  poll_rate)
private

Main-Function of keyboard thread.

Parameters
poll_rateRate (Hz) in which the keyboard will be polled for input.

Definition at line 136 of file scene_configurator.cpp.

void SceneConfigurator::objectInputCallback ( const asr_msgs::AsrObject &  object)
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.

Parameters
objectROS object msgs from which information is extracted.

Definition at line 236 of file scene_configurator.cpp.

void SceneConfigurator::printEstimations ( )
private

Definition at line 307 of file scene_configurator.cpp.

void SceneConfigurator::printHelpText ( )
private

Definition at line 337 of file scene_configurator.cpp.

void SceneConfigurator::printStatus ( )
private

Definition at line 369 of file scene_configurator.cpp.

void SceneConfigurator::processConfiguration ( )
private

Wrapper for the passed function processConfigFunc.

Definition at line 279 of file scene_configurator.cpp.

void SceneConfigurator::processKeyboardInput ( )
private

Definition at line 155 of file scene_configurator.cpp.

void SceneConfigurator::updateVisualizationCallback ( const ros::TimerEvent e)
private

Callback to update visualization.

Parameters
eTimer event with no meaning to us beyond its existence.

Definition at line 410 of file scene_configurator.cpp.

Member Data Documentation

bool SceneConfigurator::automatic_processing_active_
private

Definition at line 82 of file scene_configurator.hpp.

ros::Timer SceneConfigurator::automatic_processing_timer_
private

Definition at line 71 of file scene_configurator.hpp.

SceneConfiguratorData* SceneConfigurator::data_
private

Definition at line 70 of file scene_configurator.hpp.

bool SceneConfigurator::key_pressed_
private

Definition at line 88 of file scene_configurator.hpp.

boost::thread* SceneConfigurator::keyboard_thread_
private

Definition at line 85 of file scene_configurator.hpp.

termios SceneConfigurator::modified_terminal_settings_
private

Definition at line 87 of file scene_configurator.hpp.

ros::NodeHandle SceneConfigurator::nh_
private

Definition at line 67 of file scene_configurator.hpp.

ros::Subscriber SceneConfigurator::object_input_subscriber_
private

Definition at line 92 of file scene_configurator.hpp.

VIZ::ObjectModelVisualizerRVIZ* SceneConfigurator::object_model_visualizer_
private

Definition at line 98 of file scene_configurator.hpp.

IH::ObjectConverterPtr SceneConfigurator::object_msg_converter_
private

Definition at line 69 of file scene_configurator.hpp.

ros::CallbackQueue SceneConfigurator::object_queue_
private

Definition at line 91 of file scene_configurator.hpp.

termios SceneConfigurator::original_terminal_settings_
private

Definition at line 86 of file scene_configurator.hpp.

ProcessConfigurationFunction SceneConfigurator::processConfigurationFunc_
private

Definition at line 74 of file scene_configurator.hpp.

ProcessKeyboardInputFunction SceneConfigurator::processKeyboardInputFunc_
private

Definition at line 75 of file scene_configurator.hpp.

ProcessObjectInputFunction SceneConfigurator::processObjectInputFunc_
private

Definition at line 76 of file scene_configurator.hpp.

ros::NodeHandlePtr SceneConfigurator::ptu_
private

Definition at line 94 of file scene_configurator.hpp.

ros::AsyncSpinner* SceneConfigurator::spinner_
private

Definition at line 93 of file scene_configurator.hpp.

bool SceneConfigurator::use_only_marked_objects_
private

Definition at line 80 of file scene_configurator.hpp.

ros::Publisher SceneConfigurator::visualization_publisher_
private

Definition at line 97 of file scene_configurator.hpp.

ros::Timer SceneConfigurator::visualization_timer_
private

Definition at line 99 of file scene_configurator.hpp.


The documentation for this class was generated from the following files:


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