From c3ce98d1af587ea04d748362e40878f034a7243b Mon Sep 17 00:00:00 2001 From: Vatan Aksoy Tezer Date: Fri, 28 May 2021 19:00:43 +0000 Subject: [PATCH] Remove sdf Signed-off-by: Vatan Aksoy Tezer --- .../launch/joint_states.launch.py | 11 +- ros_ign_gazebo_demos/models/rrbot.sdf | 170 ------------------ ros_ign_gazebo_demos/models/rrbot.xacro | 61 +++++-- 3 files changed, 50 insertions(+), 192 deletions(-) delete mode 100644 ros_ign_gazebo_demos/models/rrbot.sdf diff --git a/ros_ign_gazebo_demos/launch/joint_states.launch.py b/ros_ign_gazebo_demos/launch/joint_states.launch.py index 0f92d0b6..c6296bd7 100644 --- a/ros_ign_gazebo_demos/launch/joint_states.launch.py +++ b/ros_ign_gazebo_demos/launch/joint_states.launch.py @@ -43,11 +43,10 @@ def generate_launch_description(): ) # Spawn - rrbot_sdf = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.sdf') spawn = Node(package='ros_ign_gazebo', executable='create', arguments=[ '-name', 'rrbot', - '-file', rrbot_sdf, + '-topic', 'robot_description', ], output='screen', ) @@ -68,13 +67,6 @@ def generate_launch_description(): output='screen' ) - # Static TF between world and robot - world_static_tf = Node(package='tf2_ros', - executable='static_transform_publisher', - name='world_static_tf', - output='log', - arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'base_link', 'world']) - return LaunchDescription( [ # Nodes and Launches @@ -82,7 +74,6 @@ def generate_launch_description(): spawn, bridge, robot_state_publisher, - world_static_tf, rviz, ] ) diff --git a/ros_ign_gazebo_demos/models/rrbot.sdf b/ros_ign_gazebo_demos/models/rrbot.sdf deleted file mode 100644 index c5743226..00000000 --- a/ros_ign_gazebo_demos/models/rrbot.sdf +++ /dev/null @@ -1,170 +0,0 @@ - - - - - 0 0 0 0 -0 0 - 100 - - 1 - 0 - 0 - 1 - 0 - 1 - - - - - base_link - link1 - - - 0 0 0 0 -0 0 - - 0 0 1 0 -0 0 - 1 - - 0.334167 - 0 - 0 - 0.334167 - 0 - 0.00166667 - - - - 0 0 1 0 -0 0 - - - 0.1 0.1 2 - - - - - 0 0 1 0 -0 0 - - - 0.1 0.1 2 - - - - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - - - - - 0 0.1 1.95 0 -0 0 - link1 - link2 - - 0 1 0 - - -1e+16 - 1e+16 - - - 0.7 - 0 - 0 - 0 - - - - - 0 0 0 0 -0 0 - - 0 0 0.45 0 -0 0 - 1 - - 0.0841667 - 0 - 0 - 0.0841667 - 0 - 0.00166667 - - - - 0 0 0.45 0 -0 0 - - - 0.1 0.1 1 - - - - - 0 0 0.45 0 -0 0 - - - 0.1 0.1 1 - - - - 0 0 0 1 - 0 0 0 1 - 0 0 0 1 - - - - - 0 0.1 0.9 0 -0 0 - link2 - link3 - - 0 1 0 - - -1e+16 - 1e+16 - - - 0.7 - 0 - 0 - 0 - - - - - 0 0 0 0 -0 0 - - 0 0 0.45 0 -0 0 - 1 - - 0.0841667 - 0 - 0 - 0.0841667 - 0 - 0.00166667 - - - - 0 0 0.45 0 -0 0 - - - 0.1 0.1 1 - - - - - 0 0 0.45 0 -0 0 - - - 0.1 0.1 1 - - - - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - 1 0.423529412 0.039215686 1 - - - - - - - - - diff --git a/ros_ign_gazebo_demos/models/rrbot.xacro b/ros_ign_gazebo_demos/models/rrbot.xacro index 9eb711cf..782154e3 100644 --- a/ros_ign_gazebo_demos/models/rrbot.xacro +++ b/ros_ign_gazebo_demos/models/rrbot.xacro @@ -21,10 +21,10 @@ - + - + @@ -49,9 +49,9 @@ + ixx="${mass / 12.0 * (width*width + height1*height1)}" ixy="0.0" ixz="0.0" + iyy="${mass / 12.0 * (height1*height1 + width*width)}" iyz="0.0" + izz="${mass / 12.0 * (width*width + width*width)}"/> @@ -75,7 +75,7 @@ - + @@ -84,9 +84,9 @@ + ixx="${mass / 12.0 * (width*width + height2*height2)}" ixy="0.0" ixz="0.0" + iyy="${mass / 12.0 * (height2*height2 + width*width)}" iyz="0.0" + izz="${mass / 12.0 * (width*width + width*width)}"/> @@ -119,10 +119,47 @@ + ixx="${mass / 12.0 * (width*width + height3*height3)}" ixy="0.0" ixz="0.0" + iyy="${mass / 12.0 * (height3*height3 + width*width)}" iyz="0.0" + izz="${mass / 12.0 * (width*width + width*width)}"/> + + + + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + 0.2 + 0.2 + + 0 0 0 1 + 0 0 0 1 + 0 0 0 1 + + + + + + 0.2 + 0.2 + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + + + \ No newline at end of file