Browse Source

Merge pull request #102 from hello-robot/feature/gazebo_dex_wrist

Feature/gazebo dex wrist
dev/noetic
Mohamed Fazil 1 year ago
committed by GitHub
parent
commit
30522b4013
No known key found for this signature in database GPG Key ID: 4AEE18F83AFDEB23
6 changed files with 700 additions and 24 deletions
  1. +15
    -15
      stretch_description/urdf/stretch_description.xacro
  2. +15
    -0
      stretch_gazebo/config/dex_wrist.yaml
  3. +16
    -3
      stretch_gazebo/launch/gazebo.launch
  4. +18
    -4
      stretch_gazebo/nodes/keyboard_teleop_gazebo
  5. +634
    -0
      stretch_gazebo/urdf/stretch_gazebo_dex_wrist.urdf.xacro
  6. +2
    -2
      stretch_gazebo/urdf/stretch_gazebo_standard_gripper.urdf.xacro

+ 15
- 15
stretch_description/urdf/stretch_description.xacro View File

@ -1,15 +1,15 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch">
<xacro:include filename="stretch_gripper.xacro" />
<!--<xacro:include filename="stretch_gripper_with_puller.xacro" />-->
<!--<xacro:include filename="stretch_dry_erase_marker.xacro" />-->
<xacro:include filename="stretch_main.xacro" />
<xacro:include filename="stretch_aruco.xacro" />
<xacro:include filename="stretch_d435i.xacro" />
<xacro:include filename="stretch_laser_range_finder.xacro" />
<xacro:include filename="stretch_base_imu.xacro" />
<xacro:include filename="stretch_respeaker.xacro" />
</robot>
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch">
<xacro:include filename="stretch_gripper.xacro" />
<!--<xacro:include filename="stretch_gripper_with_puller.xacro" />-->
<!--<xacro:include filename="stretch_dry_erase_marker.xacro" />-->
<xacro:include filename="stretch_main.xacro" />
<xacro:include filename="stretch_aruco.xacro" />
<xacro:include filename="stretch_d435i.xacro" />
<xacro:include filename="stretch_laser_range_finder.xacro" />
<xacro:include filename="stretch_base_imu.xacro" />
<xacro:include filename="stretch_respeaker.xacro" />
</robot>

+ 15
- 0
stretch_gazebo/config/dex_wrist.yaml View File

@ -0,0 +1,15 @@
stretch_dex_wrist_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- joint_wrist_pitch
- joint_wrist_roll
allow_partial_joints_goal: true
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
joint_gripper_finger_right: {trajectory: 0.1, goal: 0.1}
joint_gripper_finger_left: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10

+ 16
- 3
stretch_gazebo/launch/gazebo.launch View File

@ -6,10 +6,14 @@
<arg name="headless" default="false"/> <arg name="headless" default="false"/>
<arg name="debug" default="false"/> <arg name="debug" default="false"/>
<arg name="rviz" default="false"/> <arg name="rviz" default="false"/>
<arg name="model" default="$(find stretch_gazebo)/urdf/stretch_gazebo.urdf.xacro"/>
<arg name="gpu_lidar" default="false"/> <arg name="gpu_lidar" default="false"/>
<arg name="visualize_lidar" default="false"/> <arg name="visualize_lidar" default="false"/>
<arg name="world" default="worlds/empty.world"/> <arg name="world" default="worlds/empty.world"/>
<arg name="dex_wrist" default="false"/>
<param name="stretch_gazebo/dex_wrist" type="bool" value="$(arg dex_wrist)"/>
<arg name="model" value="$(find stretch_gazebo)/urdf/stretch_gazebo_standard_gripper.urdf.xacro" unless="$(arg dex_wrist)"/>
<arg name="model" value="$(find stretch_gazebo)/urdf/stretch_gazebo_dex_wrist.urdf.xacro" if="$(arg dex_wrist)"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch"> <include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)" /> <arg name="world_name" value="$(arg world)" />
@ -21,7 +25,8 @@
<arg name="verbose" value="true"/> <arg name="verbose" value="true"/>
</include> </include>
<param name="robot_description" command="$(find xacro)/xacro $(arg model) gpu_lidar:=$(arg gpu_lidar) visualize_lidar:=$(arg visualize_lidar)" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model) gpu_lidar:=$(arg gpu_lidar) visualize_lidar:=$(arg visualize_lidar)"/>
<!-- push robot_description to factory and spawn robot in gazebo --> <!-- push robot_description to factory and spawn robot in gazebo -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
@ -50,8 +55,16 @@
<rosparam command="load" <rosparam command="load"
file="$(find stretch_gazebo)/config/gripper.yaml" /> file="$(find stretch_gazebo)/config/gripper.yaml" />
<rosparam command="load"
file="$(find stretch_gazebo)/config/dex_wrist.yaml" if="$(arg dex_wrist)"/>
<node name="stretch_controller_spawner" pkg="controller_manager" type="spawner"
args="stretch_joint_state_controller stretch_diff_drive_controller stretch_arm_controller stretch_head_controller stretch_gripper_controller"
unless="$(arg dex_wrist)"/>
<node name="stretch_controller_spawner" pkg="controller_manager" type="spawner" <node name="stretch_controller_spawner" pkg="controller_manager" type="spawner"
args="stretch_joint_state_controller stretch_diff_drive_controller stretch_arm_controller stretch_head_controller stretch_gripper_controller"/>
args="stretch_joint_state_controller stretch_diff_drive_controller stretch_arm_controller stretch_head_controller stretch_gripper_controller stretch_dex_wrist_controller"
if="$(arg dex_wrist)"/>
<node name="publish_ground_truth_odom" pkg="stretch_gazebo" type="publish_ground_truth_odom.py" output="screen"/> <node name="publish_ground_truth_odom" pkg="stretch_gazebo" type="publish_ground_truth_odom.py" output="screen"/>

+ 18
- 4
stretch_gazebo/nodes/keyboard_teleop_gazebo View File

@ -180,6 +180,7 @@ class KeyboardTeleopNode:
self.rate = 10.0 self.rate = 10.0
self.joint_state = None self.joint_state = None
self.twist = Twist() self.twist = Twist()
self.dex_wrist_control = False
def joint_states_callback(self, joint_state): def joint_states_callback(self, joint_state):
self.joint_state = joint_state self.joint_state = joint_state
@ -197,8 +198,7 @@ class KeyboardTeleopNode:
trajectory_goal.goal_time_tolerance = rospy.Time(1.0) trajectory_goal.goal_time_tolerance = rospy.Time(1.0)
joint_name = command['joint'] joint_name = command['joint']
if joint_name in ['joint_lift', 'joint_wrist_yaw', 'joint_head_pan', 'joint_head_tilt']:
if joint_name in ['joint_lift', 'joint_wrist_yaw', 'joint_wrist_roll', 'joint_wrist_pitch', 'joint_head_pan', 'joint_head_tilt']:
trajectory_goal.trajectory.joint_names = [joint_name] trajectory_goal.trajectory.joint_names = [joint_name]
joint_index = joint_state.name.index(joint_name) joint_index = joint_state.name.index(joint_name)
joint_value = joint_state.position[joint_index] joint_value = joint_state.position[joint_index]
@ -221,8 +221,9 @@ class KeyboardTeleopNode:
trajectory_goal.trajectory.points = [point] trajectory_goal.trajectory.points = [point]
trajectory_goal.trajectory.header.stamp = rospy.Time.now() trajectory_goal.trajectory.header.stamp = rospy.Time.now()
self.trajectory_client.send_goal(trajectory_goal)
self.trajectory_client.wait_for_result()
if self.trajectory_client:
self.trajectory_client.send_goal(trajectory_goal)
self.trajectory_client.wait_for_result()
def trajectory_client_selector(self, command): def trajectory_client_selector(self, command):
self.trajectory_client = None self.trajectory_client = None
@ -236,6 +237,9 @@ class KeyboardTeleopNode:
self.trajectory_client = self.trajectory_head_client self.trajectory_client = self.trajectory_head_client
if joint == 'joint_gripper_finger_right' or joint == 'joint_gripper_finger_left': if joint == 'joint_gripper_finger_right' or joint == 'joint_gripper_finger_left':
self.trajectory_client = self.trajectory_gripper_client self.trajectory_client = self.trajectory_gripper_client
if self.dex_wrist_control:
if joint == 'joint_wrist_roll' or joint == 'joint_wrist_pitch':
self.trajectory_client = self.trajectory_dex_wrist_client
if joint == 'translate_mobile_base' or joint == 'rotate_mobile_base': if joint == 'translate_mobile_base' or joint == 'rotate_mobile_base':
if joint == 'translate_mobile_base': if joint == 'translate_mobile_base':
if 'inc' in command: if 'inc' in command:
@ -252,6 +256,10 @@ class KeyboardTeleopNode:
def main(self): def main(self):
rospy.init_node('keyboard_teleop_gazebo') rospy.init_node('keyboard_teleop_gazebo')
try:
self.dex_wrist_control = rospy.get_param('stretch_gazebo/dex_wrist', default=False)
except KeyError:
self.dex_wrist_control = False
self.trajectory_gripper_client = actionlib.SimpleActionClient( self.trajectory_gripper_client = actionlib.SimpleActionClient(
'/stretch_gripper_controller/follow_joint_trajectory', FollowJointTrajectoryAction) '/stretch_gripper_controller/follow_joint_trajectory', FollowJointTrajectoryAction)
@ -265,6 +273,12 @@ class KeyboardTeleopNode:
FollowJointTrajectoryAction) FollowJointTrajectoryAction)
server_reached = self.trajectory_arm_client.wait_for_server(timeout=rospy.Duration(60.0)) server_reached = self.trajectory_arm_client.wait_for_server(timeout=rospy.Duration(60.0))
if self.dex_wrist_control:
rospy.loginfo("Dex Wrist Control Activated")
self.trajectory_dex_wrist_client = actionlib.SimpleActionClient('/stretch_dex_wrist_controller/follow_joint_trajectory',
FollowJointTrajectoryAction)
server_reached = self.trajectory_dex_wrist_client.wait_for_server(timeout=rospy.Duration(60.0))
self.cmd_vel_pub = rospy.Publisher('/stretch_diff_drive_controller/cmd_vel', Twist, queue_size=10) self.cmd_vel_pub = rospy.Publisher('/stretch_diff_drive_controller/cmd_vel', Twist, queue_size=10)
rospy.Subscriber('/joint_states', JointState, self.joint_states_callback) rospy.Subscriber('/joint_states', JointState, self.joint_states_callback)

+ 634
- 0
stretch_gazebo/urdf/stretch_gazebo_dex_wrist.urdf.xacro View File

@ -0,0 +1,634 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch">
<xacro:arg name="gpu_lidar" default="false" />
<xacro:arg name="visualize_lidar" default="false" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_main.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_aruco.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_d435i.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_laser_range_finder.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_respeaker.xacro" />
<xacro:include filename="$(find stretch_description)/urdf/stretch_dex_wrist.xacro" />
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
</plugin>
</gazebo>
<!-- Base and Drive -->
<gazebo reference="base_link">
<material>Gazebo/Gray</material>
</gazebo>
<gazebo reference="link_right_wheel">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Blue</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_left_wheel">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Blue</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="caster_link">
<turnGravityOff>false</turnGravityOff>
<minDepth>0.001</minDepth>
<material>Gazebo/Blue</material>
<mu1>0.0</mu1>
<mu2>0.0</mu2>
</gazebo>
<transmission name="right_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="right_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_right_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="left_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="left_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_left_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Sensors -->
<!-- Realsense D435i -->
<gazebo reference="camera_color_frame">
<sensor name="color" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>RGB_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra1_frame">
<sensor name="ired1" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_infra2_frame">
<sensor name="ired2" type="camera">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>L_INT8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo reference="camera_depth_frame">
<sensor name="depth" type="depth">
<pose frame="">0 0 0 0 0 0</pose>
<camera name="__default__">
<horizontal_fov>1.5009831567151233</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>0</visualize>
</sensor>
</gazebo>
<gazebo>
<plugin name="camera" filename="librealsense_gazebo_plugin.so">
<depthUpdateRate>30</depthUpdateRate>
<colorUpdateRate>30</colorUpdateRate>
<infraredUpdateRate>30</infraredUpdateRate>
<depthTopicName>depth/image_raw</depthTopicName>
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
<colorTopicName>color/image_raw</colorTopicName>
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
<infrared1TopicName>infrared/image_raw</infrared1TopicName>
<infrared1CameraInfoTopicName>infrared/camera_info</infrared1CameraInfoTopicName>
<infrared2TopicName>infrared2/image_raw</infrared2TopicName>
<infrared2CameraInfoTopicName>infrared2/camera_info</infrared2CameraInfoTopicName>
<colorOpticalframeName>camera_color_optical_frame</colorOpticalframeName>
<depthOpticalframeName>camera_depth_optical_frame</depthOpticalframeName>
<infrared1OpticalframeName>camera_left_ir_optical_frame</infrared1OpticalframeName>
<infrared2OpticalframeName>camera_right_ir_optical_frame</infrared2OpticalframeName>
<rangeMinDepth>0.1</rangeMinDepth>
<rangeMaxDepth>10</rangeMaxDepth>
<pointCloud>1</pointCloud>
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
<pointCloudCutoff>0.15</pointCloudCutoff>
<pointCloudCutoffMax>10</pointCloudCutoffMax>
</plugin>
</gazebo>
<gazebo reference="camera_gyro_frame">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<visualize>false</visualize>
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<topicName>camera/imu/data</topicName>
<bodyName>camera_gyro_frame</bodyName>
<updateRateHZ>50.0</updateRateHZ>
<gaussianNoise>0.001</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>camera_gyro_frame</frameName>
<initialOrientationAsReference>false</initialOrientationAsReference>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<!-- Aruco -->
<gazebo reference="link_aruco_right_base">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="link_aruco_left_base">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="link_aruco_shoulder">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="link_aruco_top_wrist">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="link_aruco_inner_wrist">
<material>Gazebo/Black</material>
</gazebo>
<!-- Respeaker -->
<gazebo reference="respeaker_base">
<material>Gazebo/Green</material>
</gazebo>
<!-- Non GPU LIDAR -->
<xacro:unless value="$(arg gpu_lidar)">
<gazebo reference="laser">
<material>Gazebo/Black</material>
<sensor type="ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg visualize_lidar)</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>2000</samples>
<resolution>1</resolution>
<min_angle>-0.9</min_angle>
<max_angle>5.0</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:unless>
<!-- GPU LIDAR -->
<xacro:if value="$(arg gpu_lidar)">
<gazebo reference="laser">
<material>Gazebo/Black</material>
<sensor type="gpu_ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg visualize_lidar)</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>2000</samples>
<resolution>1</resolution>
<min_angle>-0.9</min_angle>
<max_angle>5.0</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lidar_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:if>
<!-- Base IMU -->
<gazebo reference="base_link">
<gravity>true</gravity>
<sensor name="base_imu" type="imu">
<always_on>true</always_on>
<visualize>false</visualize>
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<topicName>imu/data</topicName>
<bodyName>base_link</bodyName>
<updateRateHZ>25.0</updateRateHZ>
<gaussianNoise>0.001</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>base_link</frameName>
<initialOrientationAsReference>false</initialOrientationAsReference>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<!-- Wrist IMU -->
<gazebo reference="link_wrist_yaw">
<gravity>true</gravity>
<sensor name="wrist_imu" type="imu">
<always_on>true</always_on>
<visualize>false</visualize>
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<topicName>wrist_imu/data</topicName>
<bodyName>link_wrist_yaw</bodyName>
<updateRateHZ>25.0</updateRateHZ>
<gaussianNoise>0.001</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>link_wrist_yaw</frameName>
<initialOrientationAsReference>false</initialOrientationAsReference>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<!-- Lift -->
<gazebo reference="link_lift">
<mu1 value="10000.0"/>
<mu2 value="10000.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Black</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_mast">
<material>Gazebo/Gray</material>
</gazebo>
<transmission name="trans_lift">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_lift">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_lift">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Arm -->
<gazebo reference="link_arm_l0">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_arm_l1">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_arm_l2">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_arm_l3">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_arm_l4">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="trans_arm_l0">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_arm_l0" >
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_arm_l0">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_arm_l1">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_arm_l1" >
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_arm_l1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_arm_l2">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_arm_l2" >
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_arm_l2">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_arm_l3">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_arm_l3" >
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_arm_l3">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Wrist -->
<gazebo reference="link_wrist_yaw">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Black</material>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="trans_wrist_yaw">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_wrist_yaw" >
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_wrist_yaw">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Head -->
<gazebo reference="link_head">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<material>Gazebo/Gray</material>
</gazebo>
<gazebo reference="link_head_tilt">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_head_pan">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="trans_head_pan">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_head_pan">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_head_pan">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_head_tilt">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_head_tilt">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_head_tilt">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<!--Dex Wrist-->
<gazebo reference="link_wrist_yaw_bottom">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_wrist_pitch">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_wrist_roll">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_straight_gripper">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_gripper_finger_right">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_gripper_fingertip_right">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Black</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_gripper_finger_left">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Gray</material>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="link_gripper_fingertip_left">
<mu1 value="100.0"/>
<mu2 value="200.0"/>
<kp value="10000000.0" />
<kd value="100.0" />
<material>Gazebo/Black</material>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="trans_wrist_pitch">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_wrist_pitch">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_wrist_pitch">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_wrist_roll">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_wrist_roll">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_wrist_roll">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<!-- Gripper -->
<transmission name="trans_gripper_finger_left">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_gripper_finger_left">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_gripper_finger_left">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="trans_gripper_finger_right">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="motor_gripper_finger_right">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="joint_gripper_finger_right">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
</robot>

stretch_gazebo/urdf/stretch_gazebo.urdf.xacro → stretch_gazebo/urdf/stretch_gazebo_standard_gripper.urdf.xacro View File

@ -569,7 +569,7 @@
<material>Gazebo/Black</material> <material>Gazebo/Black</material>
<minDepth>0.001</minDepth> <minDepth>0.001</minDepth>
</gazebo> </gazebo>
<gazebo reference="link_gripper"> <gazebo reference="link_gripper">
<mu1 value="100.0"/> <mu1 value="100.0"/>
<mu2 value="200.0"/> <mu2 value="200.0"/>
@ -598,4 +598,4 @@
</joint> </joint>
</transmission> </transmission>
</robot>
</robot>

Loading…
Cancel
Save