this is my first post about ROS and Gazebo also I am new in ROS.
I spawn KUKA robot in Gazebo using urdf file from KUKA github repository
following answer from this question I spawned my urdf file in gazebo simulator and KUKA robot appeared in simulator but problem is that is lying down like is attached on floor for some reason.
Here is picture in Gazebo:
This is my launch file:
<launch>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-file $(find kuka_kr210_support)/urdf/kr210l150.urdf -urdf -z 1 -model baxter" />
</launch>
EDIT: I fixed base link for the world, added transmission, controllers for each axis and gazebo plugin. now my urdf file looks like this:
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from kr16_2.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--Generates a urdf from the macro in kr16_2_macro.xacro -->
<robot name="kuka_kr16_2" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- LINKS -->
<!-- base link -->
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<!-- link 1 (A1) -->
<link name="link_1">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_1.stl"/>
</geometry>
</collision>
</link>
<!-- link 2 -->
<link name="link_2">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_2.stl"/>
</geometry>
</collision>
</link>
<!-- link 3 -->
<link name="link_3">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_3.stl"/>
</geometry>
</collision>
</link>
<!-- link 4 -->
<link name="link_4">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_4.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_4.stl"/>
</geometry>
</collision>
</link>
<!-- link 5 -->
<link name="link_5">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_5.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_5.stl"/>
</geometry>
</collision>
</link>
<!-- link 6 -->
<link name="link_6">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_6.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_6.stl"/>
</geometry>
</collision>
</link>
<!-- tool 0 -->
<!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers.
<link name="tool0"/> -->
<!-- END LINKS -->
<!-- JOINTS -->
<!-- joint 1 (A1) -->
<joint name="joint_a1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.675"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 -1"/>
<limit effort="0" lower="-3.22885911619" upper="3.22885911619" velocity="2.72271363311"/>
</joint>
<transmission name="trans_joint_a1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a1">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- joint 2 (A2) -->
<joint name="joint_a2" type="revolute">
<origin rpy="0 0 0" xyz="0.26 0 0"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.70526034059" upper="0.610865238198" velocity="2.72271363311"/>
</joint>
<transmission name="trans_joint_a2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a2">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- joint 3 (A3) -->
<joint name="joint_a3" type="revolute">
<origin rpy="0 0 0" xyz="0.68 0 0"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.26892802759" upper="2.68780704807" velocity="2.72271363311"/>
</joint>
<transmission name="trans_joint_a3">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a3">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- joint 4 (A4) -->
<joint name="joint_a4" type="revolute">
<origin rpy="0 0 0" xyz="0.67 0 -0.035"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="5.75958653158"/>
</joint>
<transmission name="trans_joint_a4">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a4">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- joint 5 (A5) -->
<joint name="joint_a5" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.26892802759" upper="2.26892802759" velocity="5.75958653158"/>
</joint>
<transmission name="trans_joint_a5">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a5">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- joint 6 (A6) -->
<joint name="joint_a6" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="10.7337748998"/>
</joint>
<transmission name="trans_joint_a6">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a6">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<!-- tool frame - fixed frame
<joint name="joint_a6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
<origin rpy="0 1.57079632679 0" xyz="0.158 0 0"/>
</joint>
<transmission name="trans_joint_a6-tool0">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_a6-tool0">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_joint_a6-tool0">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>EffortJointInterface</hardwareInterface>
</actuator>
</transmission> -->
<!-- END JOINTS -->
<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
<link name="base"/>
<joint name="base_link-base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<!-- Gazebo world joint -->
<!-- Used for fixing robot to Gazebo 'base_link' -->
<link name="world"/>
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/kr16_2_gazebo</robotNamespace>
</plugin>
</gazebo>
</robot>
This is controller yaml:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
joint1_position_controller:
type: effort_controllers/JointPositionController
#joint: base_link__link_01
joint: joint_a1
pid: {p: 100, i: 100, d: 500.0}
joint2_position_controller:
type: effort_controllers/JointPositionController
#joint: link_01__link_02
joint: joint_a2
pid: {p: 100.0, i: 100, d: 2000.0}
joint3_position_controller:
type: effort_controllers/JointPositionController
#joint: link_02__link_03
joint: joint_a3
pid: {p: 100.0, i: 50, d: 1000.0}
joint4_position_controller:
type: effort_controllers/JointPositionController
#joint: link_03__link_04
joint: joint_a4
pid: {p: 100.0, i: 50, d: 200.0}
joint5_position_controller:
type: effort_controllers/JointPositionController
#joint: link_04__link_05
joint: joint_a5
pid: {p: 100.0, i: 50, d: 70.0}
joint6_position_controller:
type: effort_controllers/JointPositionController
#joint: link_05__link_06
joint: joint_a6
pid: {p: 100.0, i: 50, d: 70.0}
tool0_position_controller:
type: effort_controllers/JointPositionController
joint: link_06__tool0
#joint: joint1
pid: {p: 100.0, i: 50, d: 70.0}
and this is my launch file:
<?xml version="1.0"?>
<launch>
<arg name="paused" default="false"/>
<arg name="gazebo_gui" default="true"/>
<arg name="urdf_path" default="$(find kuka_kr16_support)/urdf/kr16_2_gazebo.urdf"/>
<!-- startup simulated world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" default="worlds/empty.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="gui" value="$(arg gazebo_gui)"/>
</include>
<!-- send robot urdf to param server -->
<param name="robot_description" textfile="$(arg urdf_path)" />
<!-- Load controllers -->
<rosparam ns="/kr16_2_gazebo" command="load" file="$(find kuka_kr16_moveit_gazebo)/config/joints.yaml" />
<!-- push robot_description to factory and spawn robot in gazebo at the origin, change x,y,z arguments to spawn in a different position -->
<node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot -x 0 -y 0 -z 0"
respawn="false" output="screen" />
<!-- Controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner"
respawn="false" output="screen" ns="/kr16_2_gazebo"
args="--namespace=/kr16_2_gazebo
joint_state_controller
joint1_position_controller
joint2_position_controller
joint3_position_controller
joint4_position_controller
joint5_position_controller
joint6_position_controller
--timeout 60">
</node>
</launch>
And when I launch it in terminal this is output:
WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. ... logging to /home/gazebo/.ros/log/133adcf4-5e8d-11e9-8069-000c2911adc8/roslaunch-ubuntu-3085.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB.
WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. started roslaunch server http://ubuntu:35047/
SUMMARY
PARAMETERS * /gazebo/enable_ros_network: True * /kr16_2_gazebo/joint1_position_controller/joint: joint_a1 * /kr16_2_gazebo/joint1_position_controller/pid/d: 500.0 * /kr16_2_gazebo/joint1_position_controller/pid/i: 100 * /kr16_2_gazebo/joint1_position_controller/pid/p: 100 * /kr16_2_gazebo/joint1_position_controller/type: effort_controller... * /kr16_2_gazebo/joint2_position_controller/joint: joint_a2 * /kr16_2_gazebo/joint2_position_controller/pid/d: 2000.0 * /kr16_2_gazebo/joint2_position_controller/pid/i: 100 * /kr16_2_gazebo/joint2_position_controller/pid/p: 100.0 * /kr16_2_gazebo/joint2_position_controller/type: effort_controller... * /kr16_2_gazebo/joint3_position_controller/joint: joint_a3 * /kr16_2_gazebo/joint3_position_controller/pid/d: 1000.0 * /kr16_2_gazebo/joint3_position_controller/pid/i: 50 * /kr16_2_gazebo/joint3_position_controller/pid/p: 100.0 * /kr16_2_gazebo/joint3_position_controller/type: effort_controller... * /kr16_2_gazebo/joint4_position_controller/joint: joint_a4 * /kr16_2_gazebo/joint4_position_controller/pid/d: 200.0 * /kr16_2_gazebo/joint4_position_controller/pid/i: 50 * /kr16_2_gazebo/joint4_position_controller/pid/p: 100.0 * /kr16_2_gazebo/joint4_position_controller/type: effort_controller... * /kr16_2_gazebo/joint5_position_controller/joint: joint_a5 * /kr16_2_gazebo/joint5_position_controller/pid/d: 70.0 * /kr16_2_gazebo/joint5_position_controller/pid/i: 50 * /kr16_2_gazebo/joint5_position_controller/pid/p: 100.0 * /kr16_2_gazebo/joint5_position_controller/type: effort_controller... * /kr16_2_gazebo/joint6_position_controller/joint: joint_a6 * /kr16_2_gazebo/joint6_position_controller/pid/d: 70.0 * /kr16_2_gazebo/joint6_position_controller/pid/i: 50 * /kr16_2_gazebo/joint6_position_controller/pid/p: 100.0 * /kr16_2_gazebo/joint6_position_controller/type: effort_controller... * /kr16_2_gazebo/joint_state_controller/publish_rate: 50 * /kr16_2_gazebo/joint_state_controller/type: joint_state_contr... * /kr16_2_gazebo/tool0_position_controller/joint: link_06__tool0 * /kr16_2_gazebo/tool0_position_controller/pid/d: 70.0 * /kr16_2_gazebo/tool0_position_controller/pid/i: 50 * /kr16_2_gazebo/tool0_position_controller/pid/p: 100.0 * /kr16_2_gazebo/tool0_position_controller/type: effort_controller... * /robot_description:
NODES /kr16_2_gazebo/ controller_spawner (controller_manager/spawner) / gazebo (gazebo_ros/gzserver) gazebo_gui (gazebo_ros/gzclient) spawn_gazebo_model (gazebo_ros/spawn_model)
auto-starting new master process[master]: started with pid [3096] ROS_MASTER_URI=http://localhost:11311
setting /run_id to 133adcf4-5e8d-11e9-8069-000c2911adc8 WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. process[rosout-1]: started with pid [3107] started core service [/rosout] process[gazebo-2]: started with pid [3110] process[gazebo_gui-3]: started with pid [3119] process[spawn_gazebo_model-4]: started with pid [3124] process[kr16_2_gazebo/controller_spawner-5]: started with pid [3125] WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. WARNING: Package name "KUKA_KR16_moveit_Luka1" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. [INFO] [1555229566.121403, 0.000000]: Controller Spawner: Waiting for service /kr16_2_gazebo/controller_manager/load_controller [ INFO] [1555229567.920658309]: Finished loading Gazebo ROS API Plugin. [ INFO] [1555229567.922362082]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting... [ INFO] [1555229567.927517546]: Finished loading Gazebo ROS API Plugin. [ INFO] [1555229567.928969037]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting... [INFO] [1555229569.090114, 0.000000]: Loading model XML from ros parameter robot_description [INFO] [1555229569.100970, 0.000000]: Waiting for service /gazebo/spawn_urdf_model [INFO] [1555229569.708130, 0.000000]: Calling service /gazebo/spawn_urdf_model [ INFO] [1555229569.740163120, 0.023000000]: waitForService: Service [/gazebo/set_physics_properties] is now available. [INFO] [1555229570.489737, 0.159000]: Spawn status: SpawnModel: Successfully spawned entity [ INFO] [1555229570.502446729, 0.159000000]: Physics dynamic reconfigure ready. [ INFO] [1555229570.679725950, 0.159000000]: Loading gazebo_ros_control plugin [ INFO] [1555229570.680028318, 0.159000000]: Starting gazebo_ros_control plugin in namespace: /kr16_2_gazebo [ INFO] [1555229570.680620454, 0.159000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server. [spawn_gazebo_model-4] process has finished cleanly log file: /home/gazebo/.ros/log/133adcf4-5e8d-11e9-8069-000c2911adc8/spawn_gazebo_model-4*.log [ INFO] [1555229570.868346785, 0.159000000]: Loaded gazebo_ros_control. [INFO] [1555229570.971088, 0.255000]: Controller Spawner: Waiting for service /kr16_2_gazebo/controller_manager/switch_controller [INFO] [1555229570.980829, 0.257000]: Controller Spawner: Waiting for service /kr16_2_gazebo/controller_manager/unload_controller [INFO] [1555229570.987506, 0.263000]: Loading controller: joint_state_controller [INFO] [1555229571.017423, 0.294000]: Loading controller: joint1_position_controller [INFO] [1555229571.106571, 0.377000]: Loading controller: joint2_position_controller [INFO] [1555229571.162822, 0.424000]: Loading controller: joint3_position_controller [INFO] [1555229571.229486, 0.475000]: Loading controller: joint4_position_controller [INFO] [1555229571.288503, 0.515000]: Loading controller: joint5_position_controller [INFO] [1555229571.361675, 0.563000]: Loading controller: joint6_position_controller [INFO] [1555229571.418728, 0.607000]: Controller Spawner: Loaded controllers: joint_state_controller, joint1_position_controller, joint2_position_controller, joint3_position_controller, joint4_position_controller, joint5_position_controller, joint6_position_controller [INFO] [1555229571.426332, 0.612000]: Started controllers: joint_state_controller, joint1_position_controller, joint2_position_controller, joint3_position_controller, joint4_position_controller, joint5_position_controller, joint6_position_controller
From output I can see that all controllers are loaded,to confirm it here is output of rostopic:
/clock /gazebo/link_states /gazebo/model_states /gazebo/parameter_descriptions /gazebo/parameter_updates /gazebo/set_link_state /gazebo/set_model_state /kr16_2_gazebo/joint1_position_controller/command /kr16_2_gazebo/joint1_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint1_position_controller/pid/parameter_updates /kr16_2_gazebo/joint1_position_controller/state /kr16_2_gazebo/joint2_position_controller/command /kr16_2_gazebo/joint2_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint2_position_controller/pid/parameter_updates /kr16_2_gazebo/joint2_position_controller/state /kr16_2_gazebo/joint3_position_controller/command /kr16_2_gazebo/joint3_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint3_position_controller/pid/parameter_updates /kr16_2_gazebo/joint3_position_controller/state /kr16_2_gazebo/joint4_position_controller/command /kr16_2_gazebo/joint4_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint4_position_controller/pid/parameter_updates /kr16_2_gazebo/joint4_position_controller/state /kr16_2_gazebo/joint5_position_controller/command /kr16_2_gazebo/joint5_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint5_position_controller/pid/parameter_updates /kr16_2_gazebo/joint5_position_controller/state /kr16_2_gazebo/joint6_position_controller/command /kr16_2_gazebo/joint6_position_controller/pid/parameter_descriptions /kr16_2_gazebo/joint6_position_controller/pid/parameter_updates /kr16_2_gazebo/joint6_position_controller/state /kr16_2_gazebo/joint_states /rosout /rosout_agg
and robot is just like hanging on base link, because base link is only one which has type=fixed and all other have type=revolute.
here is picture of hanging robot:
When I lift and release robot in gazebo using mouse, robot just fall down and axis are just shaking like there is no motor or any force which keeps them fixed.