## page was renamed from world_modeling/Tutorials/Tracking an unknown number of objects ## page was renamed from ros.org/wiki/world_modeling/Tutorials/Tracking an unknown number of objects ## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0=[[ROS/Tutorials|ROS tutorials]] ## descriptive title for the tutorial ## title = Tracking an unknown number of objects ## multi-line description to be displayed in search ## description = Multiple object can have the same visual appearance. Occlusions and unpredictable movements can complicate the data association is such scenarios. This tutorial shows how the world model solves the game of cups. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[wire/Tutorials/Visualizing the world model|Visualizing the world model]] ## next.1.link= ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = #################################### <> <> == Goal == In highly dynamic scenarios with occlusions and multiple objects that have the same visual appearance, data association is a challenging and non-trivial task. This tutorial shows the tracking capabilities of [[wire]] by playing the game of cups. <> == Approach == Each cup in [[wire]] is tracked by means of a constant velocity Kalman filter. Each Kalman filter has a constant velocity motion model with a high process noise, since it is known that the constant velocity motion model is only a reasonable approximation for short time intervals and measurements provide valuable new information. In order to update the Kalman filters, the data association has to be solved. A multiple hypothesis-based approach is adopted in which all possible explanations from measurements to world model objects are considered: * A measurement can originate from an object not present in the world model yet * A measurement can represent a false positive * A measurement can originate from an object already present in the world model All possible explanations form a hypothesis tree and the most probable hypothesis is used as a world state estimate. The process model and the process noise are defined in the file models/world_object_models.xml in [[wire/wire_core|wire_core]] package. {{{ #!python block=objectmodels }}} === The Models XML File Explained === Now, let's break the launch xml down. <> Here the models for the default object class are given. By adding multiple object_class elements, models can be made class specific. <> The position will be estimated using a position estimator. This estimator, defined in the package [wire_state_estimators] is a multiple model estimator that combines (i) a Kalman filter with a constant velocity motion model with (ii) a fixed state with fixed uncertainty. If updates follow each other relatively quickly, the Kalman filter is used to estimate the position. However, if no updates are received for ''kalman_timeout'' seconds, the Kalman filter makes place for a fixed state and uncertainty. This fixed state is defined by a Gaussian, the mean of which is based on the last estimated position, and the covariance is chosen to be ''fixed_pdf_cov''. == Data == In order to be able to reproduce the result shown in the video above, make sure that you have cloned and compiled [[wire]: {{{ $ git clone https://github.com/tue-robotics/wire.git $ catkin_make }}} Download the bag-file ([[attachment:demo05.bag]]) and decompress it: {{{ $ rosbag decompress demo05.bag }}} The bag file contains tfs, object detections and both rgb and depth images. The images are only included for ease of interpretation and inspection. These are not used by wire. == Reproducing the result == Start a ROS core: {{{ $ roscore }}} and set the [[Clock#Using_Simulation_Time_from_the_.2BAC8-clock_Topic|use_sim_time]] parameter to true: {{{ $ rosparam set use_sim_time true }}} Then make sure the world_object_models.xml file in the models folder of the [[wire_core]] package is configured correctly. For reproducing the result, set the following behavior model for the position attribute for object_class object: <> Now launch the world model: {{{ $ roslaunch wire_core start.launch }}} In a new terminal, launch the visualization: {{{ $ roslaunch wire_tutorials rviz_wire_kinetic.launch }}} Finally, play back the data: {{{ $ rosbag play demo05.bag --clock }}} The results should be similar to the results shown in the video above. ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE