diff --git a/darwin_apps/launch/darwin_cpp.launch b/darwin_apps/launch/darwin_cpp.launch
new file mode 100644
index 0000000000000000000000000000000000000000..b250cc9a5d04562de6653f830e87ff7ac55825b1
--- /dev/null
+++ b/darwin_apps/launch/darwin_cpp.launch
@@ -0,0 +1,14 @@
+<launch>
+
+  <arg name="robot" default="darwin" />
+  <arg name="environment" default="obstacles_env" />
+
+  <include file="$(find darwin_description)/launch/darwin_sim.launch">
+    <arg name="robot" value="$(arg robot)" />
+  </include>
+
+<!--  <include file="$(find bioloid_description)/launch/obstacles_env.launch">
+    <arg name="environment" value="$(arg environment)" />
+  </include>-->
+
+</launch>
diff --git a/darwin_control/config/darwin_cpp.yaml b/darwin_control/config/darwin_cpp.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..b4138f2f2bbceda461da6f43b762d9b1bb4ae1a2
--- /dev/null
+++ b/darwin_control/config/darwin_cpp.yaml
@@ -0,0 +1,136 @@
+darwin:
+  # Publish all joint states -----------------------------------
+  joint_state_controller:
+    type: joint_state_controller/JointStateController
+    publish_rate: 50  
+
+  darwin_controller_cpp:
+    left_sensor_foot_present: true
+    right_sensor_foot_present: true
+    serial_device: '/dev/ttyUSB1'
+    baudrate: 115200
+    slave_address: 2
+    type: effort_controllers/DarwinControllerCPP
+    joints:
+      - j_shoulder_pitch_r
+      - j_shoulder_pitch_l
+      - j_shoulder_roll_r
+      - j_shoulder_roll_l
+      - j_elbow_r
+      - j_elbow_l
+      - j_hip_yaw_r
+      - j_hip_yaw_l
+      - j_hip_roll_r
+      - j_hip_roll_l
+      - j_hip_pitch_r
+      - j_hip_pitch_l
+      - j_knee_r
+      - j_knee_l
+      - j_ankle_pitch_r
+      - j_ankle_pitch_l
+      - j_ankle_roll_r
+      - j_ankle_roll_l
+      - j_pan
+      - j_tilt
+    gains:
+      j_shoulder_pitch_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_shoulder_roll_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_elbow_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_shoulder_pitch_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_shoulder_roll_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_elbow_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_yaw_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_roll_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_pitch_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_knee_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_ankle_pitch_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_ankle_roll_l:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_yaw_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_roll_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_hip_pitch_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_knee_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_ankle_pitch_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_ankle_roll_r:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_pan:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+      j_tilt:
+        p: 16.0
+        d: 0.0
+        i: 0.0
+        i_clamp: 100
+
diff --git a/darwin_description/urdf/darwin_cpp.xacro b/darwin_description/urdf/darwin_cpp.xacro
new file mode 100755
index 0000000000000000000000000000000000000000..00dcca5b048cb52808696c1f814e2bc361971535
--- /dev/null
+++ b/darwin_description/urdf/darwin_cpp.xacro
@@ -0,0 +1,36 @@
+<robot name="darwin" xmlns:xacro="http://www.ros.org/wiki/xacro">
+ 
+  <xacro:include filename="$(find darwin_description)/urdf/darwin_low_res.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/darwin_imu.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/ids_xs.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/sensors/bno055.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_hand.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_hand.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/left_foot.xacro" />
+  <xacro:include filename="$(find darwin_description)/urdf/right_foot.xacro" />
+
+  <xacro:left_hand parent="left_arm_high">
+    <origin xyz="0.0 -0.060 0.016" rpy="-1.5707 0 0" />
+  </xacro:left_hand>
+
+  <xacro:right_hand parent="right_arm_high">
+    <origin xyz="0.0 -0.06 0.016" rpy="-1.5707 0 0" />
+  </xacro:right_hand>
+
+  <xacro:left_foot parent="left_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:left_foot>
+
+  <xacro:right_foot parent="right_leg_ankle_pitch">
+    <origin xyz="0 0 0" rpy="0 0 0" />
+  </xacro:right_foot>
+
+  <xacro:ids_xs name="darwin_cam" parent="head">
+    <origin xyz="0.0 0.005 0.045" rpy="0 -2.2777 1.5707" />
+  </xacro:ids_xs>
+
+  <xacro:bno055 name="darwin_imu" parent="base_link">
+    <origin xyz="0.0 0.0 -0.05" rpy="0 0 1.5707" />
+  </xacro:bno055>
+
+</robot>