diff --git a/rois_description/robot/human1.urdf.xacro b/rois_description/robot/human1.urdf.xacro
new file mode 100644
index 0000000000000000000000000000000000000000..d367df1ed7873d3c9942fcf0f21eed7e49a0f6ce
--- /dev/null
+++ b/rois_description/robot/human1.urdf.xacro
@@ -0,0 +1,185 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/VelocityJointInterface
+
+
+ hardware_interface/VelocityJointInterface
+ 15
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/VelocityJointInterface
+
+
+ hardware_interface/VelocityJointInterface
+ 15
+
+
+
+
+
+
+ human1
+
+
+
+
+ true
+ Gazebo/Red
+
+
+
+
+
+ true
+ Gazebo/White
+
+
+
+
+
+ true
+ Gazebo/White
+
+
+
+
+
+ true
+ Gazebo/Black
+
+
+
+
+
diff --git a/rois_gazebo/config/human1_controller.yaml b/rois_gazebo/config/human1_controller.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..ddf31bf486d4d09bde15875bda27a110713fcd34
--- /dev/null
+++ b/rois_gazebo/config/human1_controller.yaml
@@ -0,0 +1,46 @@
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 50
+
+diff_drive_controller:
+ type : "diff_drive_controller/DiffDriveController"
+ left_wheel : 'left_wheel_joint'
+ right_wheel : 'right_wheel_joint'
+ pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
+ twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
+
+ # Wheel separation and diameter. These are both optional.
+ # diff_drive_controller will attempt to read either one or both from the
+ # URDF if not specified as a parameter
+ wheel_separation : 0.3
+ wheel_radius : 0.1
+
+ # Wheel separation and radius multipliers
+ wheel_separation_multiplier: 1.0 # default: 1.0
+ wheel_radius_multiplier : 1.0 # default: 1.0
+
+ # Velocity commands timeout [s], default 0.5
+ cmd_vel_timeout: 1.0
+
+ # Base frame_id
+ base_frame_id: human1/base_footprint #default: base_link
+ odom_frame_id: human1/odom
+
+ # Velocity and acceleration limits
+ # Whenever a min_* is unspecified, default to -max_*
+ linear:
+ x:
+ has_velocity_limits : true
+ max_velocity : 2.0 # m/s
+ min_velocity : -2.0 # m/s
+ has_acceleration_limits: true
+ max_acceleration : 2.0 # m/s^2
+ min_acceleration : -2.0 # m/s^2
+ angular:
+ z:
+ has_velocity_limits : true
+ max_velocity : 1.0 # rad/s
+ min_velocity : -1.0
+ has_acceleration_limits: true
+ max_acceleration : 1.0 # rad/s^2
+ min_acceleration : -1.0
diff --git a/rois_gazebo/launch/setup_gazebo.launch b/rois_gazebo/launch/setup_gazebo.launch
index 95e9dfdb0d4d19be77bad385f3b2110662cc04d3..99fb925a5a4ef0d774e57621c90bc1ef27355eba 100644
--- a/rois_gazebo/launch/setup_gazebo.launch
+++ b/rois_gazebo/launch/setup_gazebo.launch
@@ -15,9 +15,9 @@
value="$(arg world_name)" />
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rois_gazebo/launch/spawn_robot.launch b/rois_gazebo/launch/spawn_model.launch
similarity index 72%
rename from rois_gazebo/launch/spawn_robot.launch
rename to rois_gazebo/launch/spawn_model.launch
index 9846c6640aaef168aff018b8dd8d6ec587670c06..7af09e7b7195278ab0e94c7a81207cc82525a58e 100644
--- a/rois_gazebo/launch/spawn_robot.launch
+++ b/rois_gazebo/launch/spawn_model.launch
@@ -3,21 +3,21 @@
+ default="$(find rois_description)/robot/$(arg model_name).urdf.xacro" />
-
+
-
+
-
+
+ args="-urdf -model $(arg model_name) -param robot_description $(arg init_pos)" />