change mass and camera rate
This commit is contained in:
parent
74339c0ea8
commit
50ae95d261
|
@ -331,7 +331,8 @@
|
|||
<link name="link_gripper">
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value="0.290087803254386" />
|
||||
<!-- <mass value="0.290087803254386" /> -->
|
||||
<mass value="0" />
|
||||
<inertia
|
||||
ixx="0.000122722161885507"
|
||||
ixy="2.8456952860616E-06"
|
||||
|
|
|
@ -12,8 +12,8 @@
|
|||
frame:=camera topic:=realsense
|
||||
h_fov:=1.5184351666666667 v_fov:=1.0122901111111111
|
||||
min_range:=0.105 max_range:=15
|
||||
width:=848 height:=480
|
||||
update_rate:=15
|
||||
width:=640 height:=480
|
||||
update_rate:=30
|
||||
robot_namespace:=/">
|
||||
|
||||
<!-- this link is the origin for the camera's data -->
|
||||
|
|
Loading…
Reference in New Issue