diff --git a/demoRedBall/CMakeLists.txt b/demoRedBall/CMakeLists.txt
index add7bd8..b537216 100644
--- a/demoRedBall/CMakeLists.txt
+++ b/demoRedBall/CMakeLists.txt
@@ -22,6 +22,17 @@ add_executable(${PROJECT_NAME} ${sources})
target_link_libraries(${PROJECT_NAME} ctrlLib ${YARP_LIBRARIES})
install(TARGETS ${PROJECT_NAME} DESTINATION bin)
+# world
+find_package(GAZEBO QUIET)
+if (GAZEBO_FOUND)
+ add_library(${PROJECT_NAME}-world SHARED src/world.cpp)
+ target_compile_definitions(${PROJECT_NAME}-world PRIVATE _USE_MATH_DEFINES)
+ target_include_directories(${PROJECT_NAME}-world PRIVATE ${GAZEBO_INCLUDE_DIRS})
+ target_link_libraries(${PROJECT_NAME}-world PRIVATE ${GAZEBO_LIBRARIES} ${YARP_LIBRARIES})
+ install(TARGETS ${PROJECT_NAME}-world LIBRARY DESTINATION "${CMAKE_INSTALL_LIBDIR}" COMPONENT shlib)
+ add_subdirectory(gazebo)
+endif()
+
if(NOT BUILD_BUNDLE)
icubcontrib_add_uninstall_target()
endif()
@@ -33,3 +44,4 @@ file(GLOB scripts ${CMAKE_CURRENT_SOURCE_DIR}/app/scripts/*.template
yarp_install(FILES ${conf} DESTINATION ${ICUBCONTRIB_CONTEXTS_INSTALL_DIR}/${PROJECT_NAME})
yarp_install(FILES ${scripts} DESTINATION ${ICUBCONTRIB_APPLICATIONS_TEMPLATES_INSTALL_DIR})
+
diff --git a/demoRedBall/app/conf/config-gazebo.ini b/demoRedBall/app/conf/config-gazebo.ini
new file mode 100644
index 0000000..50a2dce
--- /dev/null
+++ b/demoRedBall/app/conf/config-gazebo.ini
@@ -0,0 +1,53 @@
+[general]
+robot icubSim
+thread_period 20
+left_arm on
+right_arm on
+traj_time 1.0
+reach_tol 0.01
+eye left
+idle_tmo 5.0
+use_network off
+network network.ini
+speech on
+simulation on
+
+[torso]
+pitch on (min -10.0) (max 10.0)
+roll off
+yaw on (min -30.0) (max 30.0)
+
+[left_arm]
+grasp_enable on
+reach_offset 0.19 -0.06 0.07
+grasp_offset 0.19 0.02 0.06
+hand_orientation 0.0 -0.707106781186547 0.707106781186548 3.14159265358979
+impedance_velocity_mode on
+impedance_stiffness 0.4 0.4 0.4 0.2 0.2
+impedance_damping 0.002 0.002 0.002 0.002 0.0
+
+[right_arm]
+grasp_enable on
+reach_offset 0.19 -0.01 0.08
+grasp_offset 0.19 -0.02 0.08
+hand_orientation 0.0 -0.707106781186547 0.707106781186548 3.14159265358979
+impedance_velocity_mode on
+impedance_stiffness 0.4 0.4 0.4 0.2 0.2
+impedance_damping 0.002 0.002 0.002 0.002 0.0
+
+[home_arm]
+poss -30.0 30.0 0.0 45.0 0.0 0.0 0.0
+vels 10.0 10.0 10.0 10.0 10.0 10.0 10.0
+
+[arm_selection]
+hysteresis_thres 0.10
+
+[grasp]
+sphere_radius 0.1
+sphere_tmo 2.0
+release_tmo 4.0
+open_hand 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
+close_hand 10.0 80.0 30.0 30.0 30.0 40.0 30.0 40.0 150.0
+vels_hand 20.0 40.0 50.0 50.0 50.0 50.0 50.0 50.0 80.0
+
+[include speech "speech_English.ini"]
diff --git a/demoRedBall/app/conf/config.ini b/demoRedBall/app/conf/config.ini
index e8274f3..f3fc803 100644
--- a/demoRedBall/app/conf/config.ini
+++ b/demoRedBall/app/conf/config.ini
@@ -1,4 +1,3 @@
-
[general]
robot icub
thread_period 20
@@ -11,6 +10,7 @@ idle_tmo 5.0
use_network off
network network.ini
speech on
+simulation off
[torso]
pitch on (min -10.0) (max 10.0)
diff --git a/demoRedBall/app/scripts/demoRedBall_gazebo.xml.template b/demoRedBall/app/scripts/demoRedBall_gazebo.xml.template
new file mode 100644
index 0000000..73bf06a
--- /dev/null
+++ b/demoRedBall/app/scripts/demoRedBall_gazebo.xml.template
@@ -0,0 +1,122 @@
+
+Red-Ball Demo Gazebo
+
+
+ /icubSim/left/out
+ /iKinGazeCtrl/rpc
+ /icubSim/cartesianController/right_arm/state:o
+ /icubSim/cartesianController/left_arm/state:o
+ /wholeBodyDynamics/right_arm/FT:i
+ /wholeBodyDynamics/left_arm/FT:i
+
+
+
+ gzserver
+ grasp-ball-gazebo.sdf
+ localhost
+
+
+
+ gzclient
+ localhost
+
+
+
+ iKinGazeCtrl
+ --context gazeboCartesianControl --from iKinGazeCtrl.ini
+
+ /icubSim/torso/state:o
+ /icubSim/head/state:o
+ /icubSim/inertial
+
+
+ 5
+
+ localhost
+
+
+
+ yarprobotinterface
+ --context gazeboCartesianControl --config no_legs.xml
+
+ /icubSim/torso/state:o
+ /icubSim/left_arm/state:o
+ /icubSim/right_arm/state:o
+
+
+ 5
+
+ localhost
+
+
+
+ iKinCartesianSolver
+ --context gazeboCartesianControl --part right_arm
+
+ /icubSim/torso/state:o
+ /icubSim/right_arm/state:o
+
+ localhost
+
+
+
+ iKinCartesianSolver
+ --context gazeboCartesianControl --part left_arm
+
+ /icubSim/torso/state:o
+ /icubSim/left_arm/state:o
+
+ localhost
+
+
+
+ wholeBodyDynamics
+ --robot icubSim --autoconnect --dummy_ft --headV2 --no_legs
+
+ /icubSim/head/state:o
+ /icubSim/torso/state:o
+ /icubSim/right_arm/state:o
+ /icubSim/left_arm/state:o
+ /icubSim/inertial
+
+ localhost
+
+
+
+
+ pf3dTracker
+ --from pf3dTracker-gazebo.ini
+ pwrNode1
+
+
+
+ demoRedBall
+ --from config-gazebo.ini
+
+ /iKinGazeCtrl/rpc
+
+ pwrNode2
+
+
+
+ yarpview
+ --name /PF3DTracker_viewer --x 320 --y 0 --p 50 --compact
+ console
+
+
+
+ /icubSim/cam/left/rgbImage:o
+ /pf3dTracker/video:i
+ fast_tcp
+
+
+ /pf3dTracker/video:o
+ /PF3DTracker_viewer
+ fast_tcp
+
+
+ /pf3dTracker/data:o
+ /demoRedBall/trackTarget:i
+ fast_tcp
+
+
diff --git a/demoRedBall/gazebo/CMakeLists.txt b/demoRedBall/gazebo/CMakeLists.txt
new file mode 100644
index 0000000..f43d4d3
--- /dev/null
+++ b/demoRedBall/gazebo/CMakeLists.txt
@@ -0,0 +1,12 @@
+################################################################################
+# #
+# Copyright (C) 2020 Fondazione Istitito Italiano di Tecnologia (IIT) #
+# All Rights Reserved. #
+# #
+################################################################################
+
+# Install models
+install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/models DESTINATION share/gazebo)
+
+# Install worlds
+install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/worlds DESTINATION share/gazebo)
diff --git a/demoRedBall/gazebo/models/red-ball/model.config b/demoRedBall/gazebo/models/red-ball/model.config
new file mode 100644
index 0000000..95b8947
--- /dev/null
+++ b/demoRedBall/gazebo/models/red-ball/model.config
@@ -0,0 +1,11 @@
+
+
+
+ red-ball
+ 1.0
+ model.sdf
+
+
+ A red ball.
+
+
diff --git a/demoRedBall/gazebo/models/red-ball/model.sdf b/demoRedBall/gazebo/models/red-ball/model.sdf
new file mode 100644
index 0000000..8c8e648
--- /dev/null
+++ b/demoRedBall/gazebo/models/red-ball/model.sdf
@@ -0,0 +1,29 @@
+
+
+
+
+
+
+ 0 0 0 0 0 0
+
+ 700
+
+
+
+ 0.020
+
+
+
+
+ 0.025
+
+
+ 255 0 0 1
+ 255 0 0 1
+
+
+ false
+
+
+
+
diff --git a/demoRedBall/gazebo/worlds/grasp-ball-gazebo.sdf b/demoRedBall/gazebo/worlds/grasp-ball-gazebo.sdf
new file mode 100644
index 0000000..981a008
--- /dev/null
+++ b/demoRedBall/gazebo/worlds/grasp-ball-gazebo.sdf
@@ -0,0 +1,49 @@
+
+
+
+
+
+ model://sun
+
+
+
+
+ 0 0 10 0 -0 3.14
+
+
+
+
+ model://ground_plane
+
+
+
+
+ model://iCubGazeboV2_5_visuomanip
+ 0.0 0.0 0.63 0.0 0.0 0.0
+
+
+
+
+
+ model://red-ball
+
+
+ -0.35 0.0 0.935 0.0 0.0 0.0
+
+
+
+
+
+
+
+ -1.3907 -0.0286 0.9762 0 0.15 0
+ orbit
+ perspective
+
+
+
+
+
diff --git a/demoRedBall/src/main.cpp b/demoRedBall/src/main.cpp
index 189a83b..26a6c54 100644
--- a/demoRedBall/src/main.cpp
+++ b/demoRedBall/src/main.cpp
@@ -41,6 +41,8 @@ estimate the 3-d object position using stereo vision that needs
to be calibrated in advance relying on a feed-forward neural
network.
+Finally, a simulation modality is available to run the demo within gazebo.
+
\section lib_sec Libraries
- ctrlLib.
- iKin.
@@ -53,6 +55,10 @@ None.
The robot interface is assumed to be operative; in particular,
the ICartesianControl interface must be available. The
\ref iKinGazeCtrl must be running.
+
+In order to run the demo in simulation, such modules can be run with `--context gazeboCartesianControl`.
+A template is also available in the folder app/scripts/demoRedBall_gazebo.xml.template.
+
\section portsc_sec Ports Created
- \e /demoRedBall/trackTarget:i receives the 3-d
@@ -81,7 +87,9 @@ the ICartesianControl interface must be available. The
- \e /demoRedBall/lookSkin:rpc interfaces with the lookSkin module
(if available) and disables/enables it according when needed
- \e /demoRedBall/gui:o sends out info to update target
- within the icub_gui.
+ within the icub_gui
+- \e /demoRedBall/gazebo:o interfaces with the ball model in gazebo
+
- \e /demoRedBall/rpc remote procedure
call. Recognized remote commands:
@@ -117,6 +125,10 @@ idle_tmo 5.0
use_network off
// NN configuration file
network network.ini
+// enable the use of speech
+speech on
+// enable the simulation
+simulation off
[torso]
// joint switch (min **) (max **) [deg]; 'min', 'max' optional
@@ -209,6 +221,19 @@ by the manager at runtime. The speech file should look as follows:
"Oh my Gosh!! Where's the red ball??"
\endcode
+\section commands_sec Available commands
+
+To run the demo in gazebo, the following commands can be used:
+
+- `start`: to start the demo
+- `stop`: to stop the demo
+- `update_pose dx dy dz`: to update the ball position with respect
+to the initial position defined in the world.
+
+Note that on the real robot the demo automatically starts.
+
+\endcode
+
\section tested_os_sec Tested OS
Windows, Linux
@@ -313,6 +338,8 @@ class managerThread : public PeriodicThread
bool useRightArm;
bool useTorso;
int armSel;
+ bool simulation;
+ bool go;
PolyDriver *drvTorso, *drvHead, *drvLeftArm, *drvRightArm;
PolyDriver *drvCartLeftArm, *drvCartRightArm;
@@ -340,6 +367,7 @@ class managerThread : public PeriodicThread
RpcClient breatherRArpc;
RpcClient blinkerrpc;
RpcClient lookSkinrpc;
+ BufferedPort gazeboMoverPort;
Vector leftArmReachOffs;
Vector leftArmGraspOffs;
@@ -800,9 +828,9 @@ class managerThread : public PeriodicThread
{
yInfo("--- Target timeout => IDLE");
- steerHeadToHome();
stopControl();
steerTorsoToHome();
+ steerHeadToHome();
steerArmToHome(LEFTARM);
steerArmToHome(RIGHTARM);
@@ -1478,6 +1506,11 @@ class managerThread : public PeriodicThread
breatherRArpc.close();
blinkerrpc.close();
lookSkinrpc.close();
+ if (simulation)
+ {
+ gazeboMoverPort.interrupt();
+ gazeboMoverPort.close();
+ }
}
public:
@@ -1500,6 +1533,7 @@ class managerThread : public PeriodicThread
useTorso=bGeneral.check("torso",Value("on"),"Getting torso use flag").asString()=="on"?true:false;
useSpeech=bGeneral.check("speech",Value("on"),"Getting speech use flag").asString()=="on"?true:false;
useNetwork=bGeneral.check("use_network",Value("off"),"Getting network enable").asString()=="on"?true:false;
+ simulation=bGeneral.check("simulation",Value("off"),"Getting simulation enable").asString()=="on"?true:false;
trajTime=bGeneral.check("traj_time",Value(2.0),"Getting trajectory time").asDouble();
reachTol=bGeneral.check("reach_tol",Value(0.01),"Getting reaching tolerance").asDouble();
eyeUsed=bGeneral.check("eye",Value("left"),"Getting the used eye").asString();
@@ -1590,6 +1624,22 @@ class managerThread : public PeriodicThread
breatherRArpc.open(name+"/breather/right_arm:rpc");
blinkerrpc.open(name+"/blinker:rpc");
lookSkinrpc.open(name+"/lookSkin:rpc");
+ if (simulation)
+ {
+ go=false;
+ gazeboMoverPort.open(name+"/gazebo:o");
+ if (!Network::connect(gazeboMoverPort.getName(),"/red-ball/mover:i"))
+ {
+ yError()<<"Unable to connect to the redball mover!";
+ gazeboMoverPort.interrupt();
+ gazeboMoverPort.close();
+ return false;
+ }
+ }
+ else
+ {
+ go=true;
+ }
string fwslash="/";
@@ -1807,9 +1857,9 @@ class managerThread : public PeriodicThread
}
// steer the robot to the initial configuration
- steerHeadToHome();
stopControl();
steerTorsoToHome();
+ steerHeadToHome();
steerArmToHome(LEFTARM);
steerArmToHome(RIGHTARM);
@@ -1839,30 +1889,71 @@ class managerThread : public PeriodicThread
return true;
}
- void run()
+ bool updateBall(const double &x, const double &y, const double &z)
{
- getSensorData();
- doIdle();
- commandHead();
- selectArm();
- doReach();
-
- if (((armSel==LEFTARM) && leftGraspEnable) ||
- ((armSel==RIGHTARM) && rightGraspEnable))
+ if (simulation)
{
- doGrasp();
- doRelease();
- doWait();
+ if (gazeboMoverPort.getOutputCount() > 0)
+ {
+ Bottle pose;
+ pose.addDouble(x);
+ pose.addDouble(y);
+ pose.addDouble(z);
+ gazeboMoverPort.prepare() = pose;
+ gazeboMoverPort.writeStrict();
+ return true;
+ }
+
}
+ return false;
+ }
- commandFace();
+ void startDemo()
+ {
+ go=true;
}
- void threadRelease()
+ void stopDemo()
{
+ go=false;
+ stopControl();
+ Time::delay(1.0);
+ steerTorsoToHome();
steerHeadToHome();
+ steerArmToHome(LEFTARM);
+ steerArmToHome(RIGHTARM);
+ wentHome=true;
+ deleteGuiTarget();
+ if(useSpeech) sendSpeak(speech_idle[(int)Rand::scalar(0,speech_idle.size()-1e-3)]);
+ state=STATE_IDLE;
+ }
+
+ void run()
+ {
+ if (go)
+ {
+ getSensorData();
+ doIdle();
+ commandHead();
+ selectArm();
+ doReach();
+ if (((armSel==LEFTARM) && leftGraspEnable) ||
+ ((armSel==RIGHTARM) && rightGraspEnable))
+ {
+ doGrasp();
+ doRelease();
+ doWait();
+ }
+
+ commandFace();
+ }
+ }
+
+ void threadRelease()
+ {
stopControl();
steerTorsoToHome();
+ steerHeadToHome();
steerArmToHome(LEFTARM);
steerArmToHome(RIGHTARM);
@@ -1950,6 +2041,42 @@ class managerModule: public RFModule
return true;
}
+ bool respond(const Bottle& cmd, Bottle& reply) override
+ {
+ if (cmd.get(0).asString() == "update_pose")
+ {
+ if (cmd.size()<4)
+ {
+ yError() << "Requires x y z";
+ reply.addVocab(Vocab::encode("fail"));
+ return false;
+ }
+ double x=cmd.get(1).asDouble();
+ double y=cmd.get(2).asDouble();
+ double z=cmd.get(3).asDouble();
+ bool ok=thr->updateBall(x,y,z);
+ if (ok)
+ {
+ reply.addVocab(Vocab::encode("ok"));
+ }
+ else
+ {
+ reply.addVocab(Vocab::encode("fail"));
+ }
+ }
+ if (cmd.get(0).asString() == "start")
+ {
+ thr->startDemo();
+ reply.addVocab(Vocab::encode("ok"));
+ }
+ if (cmd.get(0).asString() == "stop")
+ {
+ thr->stopDemo();
+ reply.addVocab(Vocab::encode("ok"));
+ }
+ return true;
+ }
+
double getPeriod() { return 1.0; }
bool updateModule() { return true; }
};
diff --git a/demoRedBall/src/world.cpp b/demoRedBall/src/world.cpp
new file mode 100644
index 0000000..461acc9
--- /dev/null
+++ b/demoRedBall/src/world.cpp
@@ -0,0 +1,100 @@
+/******************************************************************************
+ * *
+ * Copyright (C) 2020 Fondazione Istituto Italiano di Tecnologia (IIT) *
+ * All Rights Reserved. *
+ * *
+ ******************************************************************************/
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include
+#include
+
+namespace gazebo {
+
+/******************************************************************************/
+class ModelMover : public gazebo::ModelPlugin
+{
+ gazebo::physics::ModelPtr model;
+ gazebo::event::ConnectionPtr renderer_connection;
+ yarp::os::BufferedPort port;
+ ignition::math::Vector3d starting_pos;
+
+ /**************************************************************************/
+ void onWorldFrame()
+ {
+ if (auto* b = port.read(false))
+ {
+ if (b->size() >= 3)
+ {
+ if (model->GetJoint("fixed_to_ground"))
+ {
+ if (model->RemoveJoint("fixed_to_ground"))
+ {
+ yInfo() << "Removed fixed_to_ground joint";
+ }
+ }
+
+ const auto x = starting_pos.X() + b->get(0).asDouble();
+ const auto y = starting_pos.Y() + b->get(1).asDouble();
+ const auto z = starting_pos.Z() + b->get(2).asDouble();
+ ignition::math::Pose3d new_pose(x, y, z, 0.0, 0.0, 0.0);
+ yInfo() << "New pose:" << x << y << z;
+ model->SetWorldPose(new_pose);
+
+ physics::LinkPtr child = model->GetLink("red-ball::root_link");
+ physics::LinkPtr parent = model->GetLink("world");
+ if (child || parent)
+ {
+ if (model->CreateJoint("fixed_to_ground", "fixed", parent, child))
+ {
+ yInfo() << "Added fixed_to_ground joint";
+ }
+ }
+ }
+ }
+ }
+
+public:
+ /**************************************************************************/
+ void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr)
+ {
+ this->model = model;
+ auto model_sdf = model->GetSDF();
+ if( model_sdf->HasElement("pose") )
+ {
+ starting_pos = model_sdf->Get("pose");
+ }
+ else
+ {
+ starting_pos = ignition::math::Vector3d(0.0, 0.0, 0.0);
+ }
+
+ port.open("/" + model->GetName() + "/mover:i");
+ auto bind = boost::bind(&ModelMover::onWorldFrame, this);
+ renderer_connection = gazebo::event::Events::ConnectWorldUpdateBegin(bind);
+ }
+
+ /**************************************************************************/
+ virtual ~ModelMover()
+ {
+ if (!port.isClosed())
+ {
+ port.close();
+ }
+ }
+};
+
+}
+
+GZ_REGISTER_MODEL_PLUGIN(gazebo::ModelMover)
diff --git a/pf3dTracker/app/conf/models/red_ball_gazebo.bmp b/pf3dTracker/app/conf/models/red_ball_gazebo.bmp
new file mode 100644
index 0000000..3abb56a
Binary files /dev/null and b/pf3dTracker/app/conf/models/red_ball_gazebo.bmp differ
diff --git a/pf3dTracker/app/conf/models/redball-gazebo.csv b/pf3dTracker/app/conf/models/redball-gazebo.csv
new file mode 100644
index 0000000..532dcf2
--- /dev/null
+++ b/pf3dTracker/app/conf/models/redball-gazebo.csv
@@ -0,0 +1,300 @@
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+0.000
+2.507
+4.974
+7.362
+9.635
+11.756
+13.691
+15.410
+16.887
+18.097
+19.021
+19.646
+19.961
+19.961
+19.646
+19.021
+18.097
+16.887
+15.410
+13.691
+11.756
+9.635
+7.362
+4.974
+2.507
+-0.000
+-2.507
+-4.974
+-7.362
+-9.635
+-11.756
+-13.691
+-15.410
+-16.887
+-18.097
+-19.021
+-19.646
+-19.961
+-19.961
+-19.646
+-19.021
+-18.097
+-16.887
+-15.410
+-13.691
+-11.756
+-9.635
+-7.362
+-4.974
+-2.507
+0.000
+3.760
+7.461
+11.044
+14.453
+17.634
+20.536
+23.115
+25.330
+27.145
+28.532
+29.469
+29.941
+29.941
+29.469
+28.532
+27.145
+25.330
+23.115
+20.536
+17.634
+14.453
+11.044
+7.461
+3.760
+-0.000
+-3.760
+-7.461
+-11.044
+-14.453
+-17.634
+-20.536
+-23.115
+-25.330
+-27.145
+-28.532
+-29.469
+-29.941
+-29.941
+-29.469
+-28.532
+-27.145
+-25.330
+-23.115
+-20.536
+-17.634
+-14.453
+-11.044
+-7.461
+-3.760
+20.000
+19.842
+19.372
+18.596
+17.526
+16.180
+14.579
+12.748
+10.717
+8.516
+6.180
+3.748
+1.256
+-1.256
+-3.748
+-6.180
+-8.516
+-10.717
+-12.748
+-14.579
+-16.180
+-17.526
+-18.596
+-19.372
+-19.842
+-20.000
+-19.842
+-19.372
+-18.596
+-17.526
+-16.180
+-14.579
+-12.748
+-10.717
+-8.516
+-6.180
+-3.748
+-1.256
+1.256
+3.748
+6.180
+8.516
+10.717
+12.748
+14.579
+16.180
+17.526
+18.596
+19.372
+19.842
+30.000
+29.763
+29.057
+27.893
+26.289
+24.271
+21.869
+19.123
+16.075
+12.773
+9.271
+5.621
+1.884
+-1.884
+-5.621
+-9.271
+-12.773
+-16.075
+-19.123
+-21.869
+-24.271
+-26.289
+-27.893
+-29.057
+-29.763
+-30.000
+-29.763
+-29.057
+-27.893
+-26.289
+-24.271
+-21.869
+-19.123
+-16.075
+-12.773
+-9.271
+-5.621
+-1.884
+1.884
+5.621
+9.271
+12.773
+16.075
+19.123
+21.869
+24.271
+26.289
+27.893
+29.057
+29.763
diff --git a/pf3dTracker/app/conf/pf3dTracker-gazebo.ini b/pf3dTracker/app/conf/pf3dTracker-gazebo.ini
new file mode 100644
index 0000000..c855cf6
--- /dev/null
+++ b/pf3dTracker/app/conf/pf3dTracker-gazebo.ini
@@ -0,0 +1,99 @@
+####################################
+#configuration file for PF3DTracker#
+####################################
+
+
+#############
+#module name#
+#############
+name /pf3dTracker
+
+#############################
+#parameters of the algorithm#
+#############################
+nParticles 900
+#nParticles number of particles used
+accelStDev 30
+#accelStDev 50 30 15
+#accelStDev standard deviation of the acceleration noise
+insideOutsideDiffWeight 1.5
+#insideOutsideDiffWeight inside-outside difference weight for the likelihood function
+colorTransfPolicy 1
+#colorTransfPolicy [0=transform the whole image | 1=only transform the pixels you need]
+
+
+
+
+#########################
+#port names and function#
+#########################
+inputVideoPort /pf3dTracker/video:i
+#inputVideoPort receives images from the grabber or the rectifying program.
+outputVideoPort /pf3dTracker/video:o
+#outputVideoPort produces images in which the contour of the estimated ball is highlighted
+outputDataPort /pf3dTracker/data:o
+#outputDataPort produces a stream of data in the format: X, Y, Z, likelihood, U, V, seeing_object
+outputParticlePort /pf3dTracker/particles:o
+#outputParticlePort produces data for the plotter. it is usually not active for performance reasons.
+inputParticlePort /pf3dTracker/particles:i
+#inputParticlePort recives hypotheses on the ball position from pf3dBottomup.
+outputAttentionPort /pf3dTracker/attention:o
+#outputAttentionPort produces data for the attention system, in terms of a peak of saliency.
+
+
+#################################
+#projection model and parameters#
+#################################
+#projectionModel [perspective|equidistance|unified]
+projectionModel perspective
+
+cameraContext gazeboCartesianControl
+cameraFile icubSimEyes.ini
+cameraGroup CAMERA_CALIBRATION_LEFT
+
+#######################
+#tracked object models#
+#######################
+#trackedObjectType [sphere|parallelogram]
+trackedObjectType sphere
+trackedObjectColorTemplate models/red_ball_gazebo.bmp
+trackedObjectShapeTemplate models/initial_ball_points_36mm_20percent.csv
+
+motionModelMatrix models/motion_model_matrix.csv
+trackedObjectTemp models/redball-gazebo.csv
+
+#######################
+#initialization method#
+#######################
+#initialization method [search|3dEstimate|2dEstimate]
+initializationMethod 3dEstimate
+initialX 0
+initialY 0
+initialZ 0.5
+
+
+####################
+#visualization mode#
+####################
+#circleVisualizationMode [0=inner and outer cirlce | 1=one circle with the correct radious] default 0. only applies to the sphere.
+circleVisualizationMode 1
+
+
+#########################
+#attention-related stuff#
+#########################
+#the tracker produces a value of likelihood at each time step. this value can be used to infer if the object it is tracking is the correct one. this is not a very robust way of doing so.
+#if likelihood>this value, then probably I'm tracking the object. 20Millions is good, 12Millions is the likelihood of Jonas Hornsteins's PC screen (false positive).
+#20Millions is a good threshold level when you have the right color model. 5M.
+likelihoodThreshold 0.005
+attentionOutputMax 300
+attentionOutputDecrease 0.99
+
+
+##########################
+#image saving preferences#
+##########################
+#save images with OpenCV?
+saveImagesWithOpencv false
+#always use the trailing slash here.
+saveImagesWithOpencvDir ./graphical_results/