From cfe8f165ae70eb5d162b5fd96bbd69ce618f3ae0 Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Wed, 23 Jun 2021 10:29:10 +0200
Subject: [PATCH] renaming

---
 CMakeLists.txt                                |  4 +-
 README.md                                     | 42 +++++++++----------
 .../ccf/controller/MoveItRobotArmController.h |  4 +-
 launch/application.launch                     | 12 +++---
 launch/application_demo.launch                | 14 +++----
 launch/application_standalone.launch          | 10 ++---
 launch/dummy_cgv.launch                       |  2 +-
 launch/dummy_cgv_and_cgv_connector.launch     |  4 +-
 launch/dummy_cgv_connector.launch             |  2 +-
 launch/simulation.launch                      | 12 +++---
 launch/simulation_demo.launch                 | 14 +++----
 launch/simulation_standalone.launch           | 10 ++---
 package.xml                                   |  6 +--
 scripts/debug_init_full_scene                 |  6 +--
 scripts/debug_init_scene                      |  6 +--
 .../controller/MoveItRobotArmController.cpp   | 20 ++++-----
 src/ccf/util/scene_controller_node.cpp        | 34 +++++++--------
 src/dummies/dummy_cgv.cpp                     |  2 +-
 src/dummies/dummy_pick_place.cpp              |  2 +-
 src/dummy_cgv_controller.cpp                  |  4 +-
 src/dummy_rag_controller_a.cpp                |  4 +-
 src/dummy_rag_controller_b.cpp                |  4 +-
 src/moveit_cgv_controller.cpp                 | 10 ++---
 23 files changed, 114 insertions(+), 114 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2fe33e6..41b68f0 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 3.0.2)
-project(cgv_connector)
+project(ccf)
 
 ## compile as C++14
 set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17")
@@ -317,7 +317,7 @@ target_link_libraries(${PROJECT_NAME}_scene_controller
 #############
 
 ## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_cgv_connector.cpp)
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_ccf.cpp)
 # if(TARGET ${PROJECT_NAME}-test)
 #   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
 # endif()
diff --git a/README.md b/README.md
index 02681fa..f68aff1 100644
--- a/README.md
+++ b/README.md
@@ -1,4 +1,4 @@
-# ROS-CGV Connection Component
+# CCF: The CeTI Cobot Framework
 
 This ROS package provides a connection between a ROS-based model and the [CGV framework](https://github.com/sgumhold/cgv).
 The purpose of this connection is to use the CGV framework to select and move elements from a scene provided by ROS
@@ -20,7 +20,7 @@ for internal and external testing.
   ```
 - Get the path to this package
   ```
-  $ rospack find cgv_connector
+  $ rospack find ccf
   ```
 - Generate the documentation
   ```
@@ -32,11 +32,11 @@ for internal and external testing.
 
 This demonstrator contains two mock-up nodes that can serve as stand-ins for future functional implementations.
 
-- `dummy_cgv` is a mock-up of the cgv framework. it connects to the ROS `cgv_connector` and waits for it to send a scene.
+- `dummy_cgv` is a mock-up of the cgv framework. it connects to the ROS `ccf` and waits for it to send a scene.
   Once a `Scene` is received, it waits two seconds and then sends a selection of a random `Box` from the scene (if there
   is one). After another two seconds, the `bin` is selected.
-- `dummy_cgv_connector` is a mock-up of the ros end of the connection, accepting connections from the CGV framework.
-  When receiving a message on topic `/cgv_connector/send_scene`, it sends a scene to the framework. It furthermore is
+- `dummy_ccf` is a mock-up of the ros end of the connection, accepting connections from the CGV framework.
+  When receiving a message on topic `/ccf/send_scene`, it sends a scene to the framework. It furthermore is
   able to receive object `Selection` messages (and currently simply prints a notification).
 
 ### Running the Example
@@ -48,22 +48,22 @@ This demonstrator contains two mock-up nodes that can serve as stand-ins for fut
   ```
   $ roscore
   ```
-- Start the `dummy_cgv_connector` and `dummy_cgv` nodes in two terminals.
-  Both are in the `cgv_connector` namespace.
+- Start the `dummy_cgv_controller` and `dummy_cgv` nodes in two terminals.
+  Both are in the `ccf` namespace.
   ```
-  $ rosrun cgv_connector dummy_cgv_connector
+  $ rosrun ccf dummy_cgv_controller
   ```
-  Note that the dummy_cgv tries to connect to the dummy_cgv_connector, so as long as the latter is not running,
+  Note that the dummy_cgv tries to connect to the dummy_cgv_controller, so as long as the latter is not running,
   warnings are logged.
   ```
-  $ rosrun cgv_connector dummy_cgv
+  $ rosrun ccf dummy_cgv
   ```
-- Trigger a transmission by publishing a string message to `/cgv_connector/send_scene`.
+- Trigger a transmission by publishing a string message to `/ccf/send_scene`.
   ```
-  $ rostopic pub -1 /cgv_connector/send_scene std_msgs/String "Some Message"
+  $ rostopic pub -1 /ccf/send_scene std_msgs/String "Some Message"
   ```
   The `dummy_cgv` node command will show the received scene. With a delay of two seconds, selections of a box and a bin
-  will be logged by the `dummy_cgv_connector`
+  will be logged by the `dummy_cgv_controller`
 
 ### Running the demo
 
@@ -71,15 +71,15 @@ This demonstrator contains two mock-up nodes that can serve as stand-ins for fut
 
 - configure the collision objects:
   ```
-  rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find cgv_connector`/config_objects.yaml
+  rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find ccf`/config_objects.yaml
   ```
 - configure the bin:
   ```
-  rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find cgv_connector`/config_bin.yaml
+  rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find ccf`/config_bin.yaml
   ```
 - configure the table: 
   ```
-  rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find cgv_connector`/config_table.yaml
+  rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find ccf`/config_table.yaml
   ```
   A parameter <safety_mode> has to be set in the configuration file to "base" or "safe", where the safe modes a safety-space around the table
 
@@ -93,16 +93,16 @@ This demonstrator contains two mock-up nodes that can serve as stand-ins for fut
 The following instructions can be used to run either the cgv dummy or the ros-connector dummy from within a docker container.
 All commands involving docker must be run as root or as a user with docker privileges.
 
-- Create a container called `cgv_connector`
+- Create a container called `ccf`
   ```
-  $ docker build --tag cgv_connector .
+  $ docker build --tag ccf .
   ```
 - Run the container, exposing the port the receiver listens on, `6576`.
   ```
-  $ docker run -it -p 6576:6576 ros4ceti/cgv:latest roslaunch cgv_connector dummy_cgv_connector.launch
+  $ docker run -it -p 6576:6576 ros4ceti/cgv:latest roslaunch ccf dummy_cgv_controller.launch
   ```
   Run the CGV dummy:
   ```
-  $ docker run -it --network host ros4ceti/cgv:latest roslaunch cgv_connector dummy_cgv.launch
+  $ docker run -it --network host ros4ceti/cgv:latest roslaunch ccf dummy_cgv.launch
   ```
-- The dummy_cgv_connector now is available and awaits NNG messages at `localhost:6576`.
+- The dummy_cgv_controller now is available and awaits NNG messages at `localhost:6576`.
diff --git a/include/ccf/controller/MoveItRobotArmController.h b/include/ccf/controller/MoveItRobotArmController.h
index 9df5f9a..5bf6351 100644
--- a/include/ccf/controller/MoveItRobotArmController.h
+++ b/include/ccf/controller/MoveItRobotArmController.h
@@ -5,7 +5,7 @@
 #ifndef CGV_CONNECTOR_WORKSPACE_MOVEITROBOTARMCONTROLLER_H
 #define CGV_CONNECTOR_WORKSPACE_MOVEITROBOTARMCONTROLLER_H
 
-#include <cgv_connector/SceneUpdate.h>
+#include <ccf/SceneUpdate.h>
 
 #include "RobotArmController.h"
 
@@ -19,7 +19,7 @@ private:
 public:
     explicit MoveItRobotArmController(ros::NodeHandle &nodeHandle, const std::string &cellName);
 
-    void updateScene(cgv_connector::SceneUpdateRequest &req, ros::ServiceClient &bin_check_client);
+    void updateScene(ccf::SceneUpdateRequest &req, ros::ServiceClient &bin_check_client);
 
     bool pickAndDrop(Object &robot, Object &object, Object &bin, bool simulateOnly) override;
     bool pickAndPlace(Object &robot, Object &object, Object &location, bool simulateOnly) override;
diff --git a/launch/application.launch b/launch/application.launch
index 97ec0b5..ae5157c 100644
--- a/launch/application.launch
+++ b/launch/application.launch
@@ -9,7 +9,7 @@
     </include>
 
     <!-- Load joint controller configurations from YAML file to parameter server -->
-    <rosparam file="$(find cgv_connector)/config/panda_control.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/panda_control.yaml" command="load" />
 
     <param name="move_group/trajectory_execution/allowed_execution_duration_scaling" value="4.0" />
     <param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />
@@ -29,13 +29,13 @@
 
     <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_realrobot.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_realrobot.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="moveit_cgv_connector" name="moveit_cgv_connector_instance" output="screen" />
+    <node pkg="ccf" type="moveit_cgv_controller" name="moveit_cgv_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
\ No newline at end of file
diff --git a/launch/application_demo.launch b/launch/application_demo.launch
index 6257cd0..80dfe36 100644
--- a/launch/application_demo.launch
+++ b/launch/application_demo.launch
@@ -9,7 +9,7 @@
     </include>
 
     <!-- Load joint controller configurations from YAML file to parameter server -->
-    <rosparam file="$(find cgv_connector)/config/panda_control.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/panda_control.yaml" command="load" />
 
     <param name="move_group/trajectory_execution/allowed_execution_duration_scaling" value="4.0" />
     <param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />
@@ -29,15 +29,15 @@
 
     <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_realrobot.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_realrobot.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="dummy_cgv" name="dummy_cgv_instance" output="screen" />
+    <node pkg="ccf" type="dummy_cgv" name="dummy_cgv_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="moveit_cgv_connector" name="moveit_cgv_connector_instance" output="screen" />
+    <node pkg="ccf" type="moveit_cgv_controller" name="moveit_cgv_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
diff --git a/launch/application_standalone.launch b/launch/application_standalone.launch
index b8e1b3c..0e82cf7 100644
--- a/launch/application_standalone.launch
+++ b/launch/application_standalone.launch
@@ -9,7 +9,7 @@
     </include>
 
     <!-- Load joint controller configurations from YAML file to parameter server -->
-    <rosparam file="$(find cgv_connector)/config/panda_control.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/panda_control.yaml" command="load" />
 
     <param name="move_group/trajectory_execution/allowed_execution_duration_scaling" value="4.0" />
     <param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />
@@ -29,11 +29,11 @@
 
     <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_realrobot.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_realrobot.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
\ No newline at end of file
diff --git a/launch/dummy_cgv.launch b/launch/dummy_cgv.launch
index 2d9d26e..3632dc3 100644
--- a/launch/dummy_cgv.launch
+++ b/launch/dummy_cgv.launch
@@ -1,3 +1,3 @@
 <launch>
-    <node pkg="cgv_connector" type="dummy_cgv" name="my_dummy_cgv" output="screen" />
+    <node pkg="ccf" type="dummy_cgv" name="my_dummy_cgv" output="screen" />
 </launch>
diff --git a/launch/dummy_cgv_and_cgv_connector.launch b/launch/dummy_cgv_and_cgv_connector.launch
index 01b9394..ebb269c 100644
--- a/launch/dummy_cgv_and_cgv_connector.launch
+++ b/launch/dummy_cgv_and_cgv_connector.launch
@@ -1,4 +1,4 @@
 <launch>
-    <node pkg="cgv_connector" type="dummy_cgv" name="my_dummy_cgv" output="screen" />
-    <node pkg="cgv_connector" type="dummy_cgv_connector" name="my_dummy_cgv_connector" output="screen" />
+    <node pkg="ccf" type="dummy_cgv" name="my_dummy_cgv" output="screen" />
+    <node pkg="ccf" type="dummy_cgv_controller" name="my_dummy_cgv_controller" output="screen" />
 </launch>
diff --git a/launch/dummy_cgv_connector.launch b/launch/dummy_cgv_connector.launch
index 6c428bb..3b28246 100644
--- a/launch/dummy_cgv_connector.launch
+++ b/launch/dummy_cgv_connector.launch
@@ -1,3 +1,3 @@
 <launch>
-    <node pkg="cgv_connector" type="dummy_cgv_connector" name="my_dummy_cgv_connector" output="screen" />
+    <node pkg="ccf" type="dummy_cgv_controller" name="my_dummy_cgv_controller" output="screen" />
 </launch>
diff --git a/launch/simulation.launch b/launch/simulation.launch
index e154383..188c537 100644
--- a/launch/simulation.launch
+++ b/launch/simulation.launch
@@ -4,17 +4,17 @@
 
 
     <node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false"
-          args="-d $(find cgv_connector)/config/config.rviz" output="screen">
+          args="-d $(find ccf)/config/config.rviz" output="screen">
         <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
     </node>
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_simulation.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_simulation.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="moveit_cgv_connector" name="moveit_cgv_connector_instance" output="screen" />
+    <node pkg="ccf" type="moveit_cgv_controller" name="moveit_cgv_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
\ No newline at end of file
diff --git a/launch/simulation_demo.launch b/launch/simulation_demo.launch
index 8f3eb93..ec5e96c 100644
--- a/launch/simulation_demo.launch
+++ b/launch/simulation_demo.launch
@@ -4,19 +4,19 @@
 
 
     <node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false"
-          args="-d $(find cgv_connector)/config/config.rviz" output="screen">
+          args="-d $(find ccf)/config/config.rviz" output="screen">
         <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
     </node>
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_simulation.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_simulation.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="dummy_cgv" name="dummy_cgv_instance" output="screen" />
+    <node pkg="ccf" type="dummy_cgv" name="dummy_cgv_instance" output="screen" />
 
-    <node pkg="cgv_connector" type="moveit_cgv_connector" name="moveit_cgv_connector_instance" output="screen" />
+    <node pkg="ccf" type="moveit_cgv_controller" name="moveit_cgv_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
\ No newline at end of file
diff --git a/launch/simulation_standalone.launch b/launch/simulation_standalone.launch
index ae1a7f8..ed05f84 100644
--- a/launch/simulation_standalone.launch
+++ b/launch/simulation_standalone.launch
@@ -4,15 +4,15 @@
 
 
     <node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="false"
-          args="-d $(find cgv_connector)/config/config.rviz" output="screen">
+          args="-d $(find ccf)/config/config.rviz" output="screen">
         <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/>
     </node>
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
-    <rosparam file="$(find cgv_connector)/config/config_simulation.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config_simulation.yaml" command="load" />
 
-    <node pkg="cgv_connector" type="scene_controller" name="scene_controller_instance" output="screen" />
+    <node pkg="ccf" type="scene_controller" name="scene_controller_instance" output="screen" />
 
-    <rosparam file="$(find cgv_connector)/config/config.yaml" command="load" />
+    <rosparam file="$(find ccf)/config/config.yaml" command="load" />
 
 </launch>
\ No newline at end of file
diff --git a/package.xml b/package.xml
index 5f81f91..803504a 100644
--- a/package.xml
+++ b/package.xml
@@ -1,8 +1,8 @@
 <?xml version="1.0"?>
 <package format="2">
-  <name>cgv_connector</name>
+  <name>ccf</name>
   <version>0.7.0</version>
-  <description>The cgv_connector plugin to connect to the controller.</description>
+  <description>The CeTI Cobot Framework</description>
 
   <!-- One maintainer tag required, multiple allowed, one person per tag -->
   <maintainer email="sebastian.ebert@tu-dresden.de">Sebastian Ebert</maintainer>
@@ -17,7 +17,7 @@
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
   <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/cgv_connector</url> -->
+  <!-- <url type="website">http://wiki.ros.org/ccf</url> -->
 
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
diff --git a/scripts/debug_init_full_scene b/scripts/debug_init_full_scene
index e0fdc9e..d3a55b2 100755
--- a/scripts/debug_init_full_scene
+++ b/scripts/debug_init_full_scene
@@ -1,7 +1,7 @@
 #!/bin/bash
 
-rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find cgv_connector`/config_table.yaml
+rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find ccf`/config_table.yaml
 sleep 3
-rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find cgv_connector`/config_bins.yaml
+rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find ccf`/config_bins.yaml
 sleep 3
-rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find cgv_connector`/config_objects_full.yaml
+rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find ccf`/config_objects_full.yaml
diff --git a/scripts/debug_init_scene b/scripts/debug_init_scene
index 3df3796..717f901 100755
--- a/scripts/debug_init_scene
+++ b/scripts/debug_init_scene
@@ -1,7 +1,7 @@
 #!/bin/bash
 
-rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find cgv_connector`/config_table.yaml
+rostopic pub -1 /scene_config/collision_table std_msgs/String -f `rospack find ccf`/config_table.yaml
 sleep 3
-rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find cgv_connector`/config_bin.yaml
+rostopic pub -1 /scene_config/collision_bin std_msgs/String -f `rospack find ccf`/config_bin.yaml
 sleep 3
-rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find cgv_connector`/config_objects.yaml
+rostopic pub -1 /scene_config/collision_objects std_msgs/String -f `rospack find ccf`/config_objects.yaml
diff --git a/src/ccf/controller/MoveItRobotArmController.cpp b/src/ccf/controller/MoveItRobotArmController.cpp
index 0c6e4cc..70e2255 100644
--- a/src/ccf/controller/MoveItRobotArmController.cpp
+++ b/src/ccf/controller/MoveItRobotArmController.cpp
@@ -10,14 +10,14 @@
 
 #include <ccf/util/scene_constructor_util.h>
 
-#include <cgv_connector/SceneUpdate.h>
-#include <cgv_connector/PickDropService.h>
-#include <cgv_connector/PickPlaceService.h>
-#include <cgv_connector/BinCheck.h>
+#include <ccf/SceneUpdate.h>
+#include <ccf/PickDropService.h>
+#include <ccf/PickPlaceService.h>
+#include <ccf/BinCheck.h>
 
 #include "ccf/controller/MoveItRobotArmController.h"
 
-void MoveItRobotArmController::updateScene(cgv_connector::SceneUpdateRequest &req, ros::ServiceClient &bin_check_client) {
+void MoveItRobotArmController::updateScene(ccf::SceneUpdateRequest &req, ros::ServiceClient &bin_check_client) {
 
     Scene newScene;
 
@@ -30,7 +30,7 @@ void MoveItRobotArmController::updateScene(cgv_connector::SceneUpdateRequest &re
             || req.ids[i] == TABLE_PILLAR_3 || req.ids[i] == TABLE_PILLAR_4) {
             object->set_type(Object_Type_UNKNOWN);
         } else {
-            cgv_connector::BinCheck srv;
+            ccf::BinCheck srv;
             srv.request.id = req.ids[i];
             bin_check_client.call(srv);
 
@@ -95,7 +95,7 @@ bool MoveItRobotArmController::pickAndDrop(Object &robot, Object &object, Object
         ROS_ERROR_STREAM("[MoveItRobotArmController] pickAndDrop with simulateOnly=false not implemented yet!");
     }
 
-    cgv_connector::PickDropService srv;
+    ccf::PickDropService srv;
     srv.request.object = object.id();
     srv.request.bin = bin.id();
     pick_drop_client.call(srv);
@@ -110,7 +110,7 @@ bool MoveItRobotArmController::pickAndPlace(Object &robot, Object &object, Objec
         ROS_ERROR_STREAM("[MoveItRobotArmController] pickAndPlace with simulateOnly=false not implemented yet!");
     }
 
-    cgv_connector::PickPlaceService srv;
+    ccf::PickPlaceService srv;
     srv.request.object = object.id();
     srv.request.pose.orientation.x = location.orientation().x();
     srv.request.pose.orientation.y = location.orientation().y();
@@ -129,8 +129,8 @@ bool MoveItRobotArmController::pickAndPlace(Object &robot, Object &object, Objec
 
 MoveItRobotArmController::MoveItRobotArmController(ros::NodeHandle &nodeHandle, const std::string &cellName)
         : RobotArmController(nodeHandle, cellName),
-          pick_drop_client(nodeHandle.serviceClient<cgv_connector::PickDropService>("/pick_drop_service")),
-          pick_place_client(nodeHandle.serviceClient<cgv_connector::PickPlaceService>("/pick_place_service")) {}
+          pick_drop_client(nodeHandle.serviceClient<ccf::PickDropService>("/pick_drop_service")),
+          pick_place_client(nodeHandle.serviceClient<ccf::PickPlaceService>("/pick_place_service")) {}
 
 bool MoveItRobotArmController::reachableObject(const Object &robot, const Object &object) {
     return false;
diff --git a/src/ccf/util/scene_controller_node.cpp b/src/ccf/util/scene_controller_node.cpp
index f43330e..d015dc9 100644
--- a/src/ccf/util/scene_controller_node.cpp
+++ b/src/ccf/util/scene_controller_node.cpp
@@ -9,11 +9,11 @@
 #include <google/protobuf/message.h>
 
 #include "connector.pb.h"
-#include "cgv_connector/SceneUpdate.h"
-#include "cgv_connector/BinCheck.h"
-#include "cgv_connector/PickDropService.h"
-#include "cgv_connector/PickPlaceService.h"
-#include "cgv_connector/PickPlace.h"
+#include "ccf/SceneUpdate.h"
+#include "ccf/BinCheck.h"
+#include "ccf/PickDropService.h"
+#include "ccf/PickPlaceService.h"
+#include "ccf/PickPlace.h"
 
 #include <moveit/planning_scene_interface/planning_scene_interface.h>
 #include <moveit/move_group_interface/move_group_interface.h>
@@ -115,7 +115,7 @@ bool pushSceneUpdate(ros::NodeHandle &n) {
 
     ROS_INFO("[SCENECONTROLLER] Creating dump of current scene.");
 
-    cgv_connector::SceneUpdate::Request req;
+    ccf::SceneUpdate::Request req;
 
     std::vector<geometry_msgs::Pose> poses;
     std::vector<shape_msgs::SolidPrimitive> primitives;
@@ -160,8 +160,8 @@ bool pushSceneUpdate(ros::NodeHandle &n) {
     req.transform.z = world_state::current_transform.z;
 
 
-    ros::ServiceClient client = n.serviceClient<cgv_connector::SceneUpdate>("/connector_node_ros_cgv/updateCgvScene");
-    cgv_connector::SceneUpdate srv;
+    ros::ServiceClient client = n.serviceClient<ccf::SceneUpdate>("/connector_node_ros_cgv/updateCgvScene");
+    ccf::SceneUpdate srv;
     srv.request = req;
     return client.call(srv);
 }
@@ -586,8 +586,8 @@ void dropObjectCallback(const std_msgs::String::ConstPtr &msg,
  * @param group a move group to plan with
  * @return true on success
  */
-bool pickAndPlaceObjectCallback(cgv_connector::PickPlaceService::Request &req,
-                                cgv_connector::PickPlaceService::Response &res, ros::NodeHandle &n,
+bool pickAndPlaceObjectCallback(ccf::PickPlaceService::Request &req,
+                                ccf::PickPlaceService::Response &res, ros::NodeHandle &n,
                                 moveit::planning_interface::PlanningSceneInterface &planning_scene_interface,
                                 moveit::planning_interface::MoveGroupInterface &group) {
 
@@ -638,8 +638,8 @@ bool pickAndPlaceObjectCallback(cgv_connector::PickPlaceService::Request &req,
  * @param res contains true if object with id is a valid bin
  * @return true
  */
-bool checkBin(cgv_connector::BinCheck::Request &req,
-              cgv_connector::BinCheck::Response &res) {
+bool checkBin(ccf::BinCheck::Request &req,
+              ccf::BinCheck::Response &res) {
     ROS_DEBUG("[SCENECONTROLLER] Received binCheck-request.");
 
     bool is_bin = isBin(req.id);
@@ -666,8 +666,8 @@ void manualScenePush(const std_msgs::String::ConstPtr &msg, ros::NodeHandle &n)
  * @param group a initialized MoveGroupInterface instance
  * @param n true on success
  */
-bool pickAndDropObjectCallback(cgv_connector::PickDropService::Request &req,
-                    cgv_connector::PickDropService::Response &res, ros::NodeHandle &n,
+bool pickAndDropObjectCallback(ccf::PickDropService::Request &req,
+                    ccf::PickDropService::Response &res, ros::NodeHandle &n,
                     moveit::planning_interface::PlanningSceneInterface &planning_scene_interface,
                     moveit::planning_interface::MoveGroupInterface &group) {
 
@@ -779,7 +779,7 @@ int main(int argc, char **argv) {
         }
 
         world_state::is_initialized = true;
-        ROS_INFO_STREAM("[SCENECONTROLLER] Initial cgv_connector setup finished.");
+        ROS_INFO_STREAM("[SCENECONTROLLER] Initial ccf setup finished.");
     }
 
     ros::Subscriber sub_co = n.subscribe<std_msgs::String>("/scene_config", 1000,
@@ -805,12 +805,12 @@ int main(int argc, char **argv) {
 
     ros::ServiceServer service = n.advertiseService("/check_bin_service", checkBin);
 
-    ros::ServiceServer pick_drop_service = n.advertiseService<cgv_connector::PickDropService::Request, cgv_connector::PickDropService::Response>(
+    ros::ServiceServer pick_drop_service = n.advertiseService<ccf::PickDropService::Request, ccf::PickDropService::Response>(
             "pick_drop_service",
             boost::bind(&pickAndDropObjectCallback, _1, _2, boost::ref(n), boost::ref(planning_scene_interface),
                         boost::ref(group)));
 
-    ros::ServiceServer pick_place_service = n.advertiseService<cgv_connector::PickPlaceService::Request, cgv_connector::PickPlaceService::Response>(
+    ros::ServiceServer pick_place_service = n.advertiseService<ccf::PickPlaceService::Request, ccf::PickPlaceService::Response>(
             "pick_place_service",
             boost::bind(&pickAndPlaceObjectCallback, _1, _2, boost::ref(n), boost::ref(planning_scene_interface),
                         boost::ref(group)));
diff --git a/src/dummies/dummy_cgv.cpp b/src/dummies/dummy_cgv.cpp
index 9025479..74e6cc6 100644
--- a/src/dummies/dummy_cgv.cpp
+++ b/src/dummies/dummy_cgv.cpp
@@ -49,7 +49,7 @@ int main(int argc, char **argv) {
 
     ros::init(argc, argv, "dummy_cgv");
 
-    ros::NodeHandle n("cgv_connector");
+    ros::NodeHandle n("ccf");
 
     if ((rv = nng_pair1_open(&sock)) != 0) {
         ROS_ERROR_STREAM("[dummyCgv] nng_pair1_open returned: " << nng_strerror(rv));
diff --git a/src/dummies/dummy_pick_place.cpp b/src/dummies/dummy_pick_place.cpp
index ba63f97..90c1b8e 100644
--- a/src/dummies/dummy_pick_place.cpp
+++ b/src/dummies/dummy_pick_place.cpp
@@ -47,7 +47,7 @@ int main(int argc, char **argv) {
 
     ros::init(argc, argv, "dummy_pick_place");
 
-    ros::NodeHandle n("cgv_connector");
+    ros::NodeHandle n("ccf");
 
     if ((rv = nng_pair1_open(&sock)) != 0) {
         ROS_ERROR_STREAM("[" << NODE_NAME << "] nng_pair1_open returned: " << nng_strerror(rv));
diff --git a/src/dummy_cgv_controller.cpp b/src/dummy_cgv_controller.cpp
index 10aa605..70e5de9 100644
--- a/src/dummy_cgv_controller.cpp
+++ b/src/dummy_cgv_controller.cpp
@@ -1,4 +1,4 @@
-/*! \file dummy_cgv_connector.cpp
+/*! \file dummy_cgv_controller.cpp
 
     A ROS node that simulates a node connected to a model-based cobotic application
 
@@ -27,7 +27,7 @@ const std::string NODE_NAME = "ros2cgv_dummy";
 
 void loadScene(DummyRobotArmController &connector) {
     // read file into string: https://stackoverflow.com/questions/2602013/read-whole-ascii-file-into-c-stdstring
-    std::string path = ros::package::getPath("cgv_connector") + "/config/config_scene.yaml";
+    std::string path = ros::package::getPath("ccf") + "/config/config_scene.yaml";
     std::ifstream t(path);
 
     if (!t.is_open()) {
diff --git a/src/dummy_rag_controller_a.cpp b/src/dummy_rag_controller_a.cpp
index b3842b7..0ad7b0b 100644
--- a/src/dummy_rag_controller_a.cpp
+++ b/src/dummy_rag_controller_a.cpp
@@ -1,4 +1,4 @@
-/*! \file dummy_cgv_connector.cpp
+/*! \file dummy_rag_controller_a.cpp
 
     A ROS node that simulates a node connected to a model-based cobotic application
 
@@ -42,7 +42,7 @@ int main(int argc, char **argv) {
     DummyRobotArmController connector{n, CELL_NAME};
 
     // only for debugging (uncomment when running without the RAG part)
-    // connector.loadScene("/home/jm/work/git/ceti/models2021/src/cgv_connector/config/config_pick_place_scene.json");
+    // connector.loadScene("/home/jm/work/git/ceti/models2021/src/ccf/config/config_pick_place_scene.json");
 
     // add an NNG connection
     std::unique_ptr<NngConnection> connection = std::make_unique<NngConnection>(cgv_address);
diff --git a/src/dummy_rag_controller_b.cpp b/src/dummy_rag_controller_b.cpp
index 91dc0b7..5a439f5 100644
--- a/src/dummy_rag_controller_b.cpp
+++ b/src/dummy_rag_controller_b.cpp
@@ -1,4 +1,4 @@
-/*! \file dummy_cgv_connector.cpp
+/*! \file dummy_rag_controller_b.cpp
 
     A ROS node that simulates a node connected to a model-based cobotic application
 
@@ -41,7 +41,7 @@ int main(int argc, char **argv) {
     DummyRobotArmController connector{n, CELL_NAME};
 
     // only for debugging (uncomment when running without the RAG part)
-    // connector.loadScene("/home/jm/work/git/ceti/models2021/src/cgv_connector/config/config_pick_place_scene.json");
+    // connector.loadScene("/home/jm/work/git/ceti/models2021/src/ccf/config/config_pick_place_scene.json");
 
     // add an MQTT connection
     std::string mqtt_address = getParameter(n, "mqtt/mqtt_address", "tcp://localhost:1883");
diff --git a/src/moveit_cgv_controller.cpp b/src/moveit_cgv_controller.cpp
index d4f5fb7..9fb5713 100644
--- a/src/moveit_cgv_controller.cpp
+++ b/src/moveit_cgv_controller.cpp
@@ -1,4 +1,4 @@
-/*! \file moveit_cgv_connector.cpp
+/*! \file moveit_cgv_controller.cpp
 
     A ROS node that controls a robot connected to a model-based cobotic application
 
@@ -15,8 +15,8 @@
 #include "connector.pb.h"
 
 
-#include <cgv_connector/BinCheck.h>
-#include <cgv_connector/SceneUpdate.h>
+#include <ccf/BinCheck.h>
+#include <ccf/SceneUpdate.h>
 
 #include "ccf/controller/MoveItRobotArmController.h"
 #include "ccf/connection/NngConnection.h"
@@ -100,8 +100,8 @@ int main(int argc, char **argv) {
 
     connector.reactToSelectionMessage(lambda);
 
-    ros::ServiceClient bin_check_client = n.serviceClient<cgv_connector::BinCheck>("/check_bin_service");
-    ros::ServiceServer get_scene_service = n.advertiseService<cgv_connector::SceneUpdateRequest, cgv_connector::SceneUpdateResponse>(
+    ros::ServiceClient bin_check_client = n.serviceClient<ccf::BinCheck>("/check_bin_service");
+    ros::ServiceServer get_scene_service = n.advertiseService<ccf::SceneUpdateRequest, ccf::SceneUpdateResponse>(
             "/connector_node_ros_cgv/updateCgvScene",
             [&currentlyPickedBox, &connector, &bin_check_client](auto &req, auto &res) {
                 ROS_INFO_STREAM("[" << NODE_NAME << "] Received a scene update from the controller.");
-- 
GitLab