diff --git a/launch/description.launch b/launch/description.launch index 040b138f0b2d0994d8cbce437bd524c579d7ce1e..d6ace37c049b0ebbe91d95c9e526bb6a5978a262 100644 --- a/launch/description.launch +++ b/launch/description.launch @@ -14,11 +14,11 @@ frame:=$(arg model_frame) mesh:=$(arg model_mesh)" /> - <node pkg="robot_state_publisher" type="state_publisher" name="state_publisher"> + <node pkg="robot_state_publisher" type="robot_state_publisher" name="state_publisher"> <param name="tf_prefix" type="string" value="/$(arg ns)"/> <param name="publish_frequency" type="double" value="20.0"/> </node> </group> -</launch> \ No newline at end of file +</launch> diff --git a/urdf/world.xacro b/urdf/world.xacro index 6a419dbdfefeaaa65b8f37658c63db9ceb0f5c54..f178ae1d0a9440cf5e2447b9b09d6761748f997e 100644 --- a/urdf/world.xacro +++ b/urdf/world.xacro @@ -5,11 +5,6 @@ <link name="$(arg parent)"/> <link name="$(arg frame)"> - <inertial> - <mass value="10000"/> - <origin xyz="0 0 0" rpy="0 0 0"/> - <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" /> - </inertial> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> @@ -31,4 +26,18 @@ <axis xyz="0 0 1"/> </joint> + <link name="$(arg frame)_body"> + <inertial> + <mass value="10000"/> + <origin xyz="0 0 0" rpy="0 0 0"/> + <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" /> + </inertial> + </link> + + <joint name="$(arg frame)2$(arg frame)_body" type="fixed"> + <parent link="$(arg frame)"/> + <child link="$(arg frame)_body"/> + <origin xyz="0 0 0" rpy="0 0 0"/> + </joint> + </robot> diff --git a/worlds/master_big.world b/worlds/master_big.world index 23aaba412c13eac2fefb258210d339c2828a2381..8d1f96b8a6557fd196c3f579b0958172ea8621a4 100644 --- a/worlds/master_big.world +++ b/worlds/master_big.world @@ -1,31 +1,13 @@ <?xml version="1.0" ?> <sdf version="1.4"> <world name="master_big"> - <!-- <include> - <uri>model://sun</uri> + <uri>model://ground_plane</uri> </include> - --> - - <light type="directional" name="sun"> - <cast_shadows>true</cast_shadows> - <pose>0 0 10 0.2 0.2 0.2</pose> - <diffuse>0.8 0.8 0.8 1</diffuse> - <specular>0.2 0.2 0.2 1</specular> - <attenuation> - <range>1000</range> - <constant>0.9</constant> - <linear>0.01</linear> - <quadratic>0.001</quadratic> - </attenuation> - <direction>-0.5 0.1 -0.9</direction> - </light> - <include> - <uri>model://ground_plane</uri> + <uri>model://sun</uri> </include> - - <model name="master_big"> + <model name="master_big"> <static>true</static> <link name="link"> <pose>0 0 0 0 0 0</pose> @@ -47,14 +29,6 @@ </visual> </link> </model> - -<gui fullscreen='0'> - <camera name='user_camera'> - <pose frame=''>10.0958 -9.41664 10.969 0 0.667643 2.2282</pose> - <view_controller>orbit</view_controller> - <projection_type>perspective</projection_type> - </camera> - </gui> </world> -</sdf> \ No newline at end of file +</sdf>