From a7bb01173e1b92eb68eb9279ef5184ce6c65fba5 Mon Sep 17 00:00:00 2001 From: Ventsi <uquzq@student.kit.edu> Date: Fri, 9 Aug 2024 00:09:08 +0200 Subject: [PATCH] Fix RViz file of simple_robot --- .../simple_robot_1dof/urdf/simple_robot.urdf | 33 +++++++++++-------- 1 file changed, 19 insertions(+), 14 deletions(-) diff --git a/ros2_ws/src/simple_robot_1dof/urdf/simple_robot.urdf b/ros2_ws/src/simple_robot_1dof/urdf/simple_robot.urdf index 3e53eaf..2eb36ab 100644 --- a/ros2_ws/src/simple_robot_1dof/urdf/simple_robot.urdf +++ b/ros2_ws/src/simple_robot_1dof/urdf/simple_robot.urdf @@ -1,17 +1,7 @@ <?xml version="1.0"?> -<robot name="simple_robot" xmlns:xacro="http://www.ros.org/wiki/xacro"> +<robot name="simple_robot"> - <link name="map"> - <origin rpy="0 0 0" xyz="0 0 0" /> - <visual> - <geometry> - <box size="0.1 0.1 0.1"/> - </geometry> - <material name="grey"> - <color rgba="0.5 0.5 0.5 1"/> - </material> - </visual> - </link> + <link name="map" /> <link name="arm1"> <visual> @@ -23,6 +13,11 @@ <color rgba="1.0 0.0 0.0 1"/> </material> </visual> + <inertial> + <origin xyz="0 0 0.355" rpy="0 0 0"/> + <mass value="5"/> + <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/> + </inertial> </link> <joint name="joint1" type="revolute"> @@ -43,13 +38,18 @@ <color rgba="0.0 1.0 0.0 1"/> </material> </visual> + <inertial> + <mass value="5"/> + <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/> + <origin xyz="-0.15 0 0" rpy="0 -1.5707 0"/> + </inertial> </link> <joint name="joint2" type="revolute"> <parent link="arm1"/> <child link="arm2"/> <origin xyz="0 0 0.71"/> - <axis xyz="1 0 0"/> + <axis xyz="0 1 0"/> <limit effort = "300" lower="-2.96705972839" upper="2.96705972839" velocity = "10" /> </joint> @@ -63,13 +63,18 @@ <color rgba="0.0 0.0 1.0 1"/> </material> </visual> + <inertial> + <mass value="5"/> + <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/> + <origin xyz="-0.15 0 0" rpy="0 -1.5707 0"/> + </inertial> </link> <joint name="joint3" type="revolute"> <parent link="arm2"/> <child link="arm3"/> <origin xyz="-0.3 0 0"/> - <axis xyz="1 0 0"/> + <axis xyz="0 1 0"/> <limit effort = "300" lower="-2.96705972839" upper="2.96705972839" velocity = "10" /> </joint> -- GitLab