建模实践3 —— 优化物理仿真模型
- 1.husky_kinova.xacro
- 2.husky_wheel宏在 wheel.urdf.xacro中定义
- 3.kinova_armlink宏、kinova_armjoint宏、kinova_virtual_link宏、kinova_virtual_joint宏在kinova_common.xacro中定义
- 4.kinova_3fingers宏在kinova_finger_set.xacro中定义
- 5.kinova_finger宏在kinova_common.xacro中定义
- 6.display_husky_kinova.launch
- 7.husky_kinova_empty_world.launch
在之前写的URDF模型基础上做以下优化:
- 使用xacro文件优化URDF模型
- 为link添加惯性参数和碰撞属性
- 为link添加gazebo标签
- 为joint添加传动装置
- 添加gazebo控制器插件
- 在gazebo中加载机器人模型
文件结构:
1.husky_kinova.xacro
<?xml version="1.0"?>
<robot name="mbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="husky_front_bumper_extend" value="$(optenv HUSKY_FRONT_BUMPER_EXTEND 0)" />
<xacro:property name="husky_rear_bumper_extend" value="$(optenv HUSKY_REAR_BUMPER_EXTEND 0)" />
<!-- Base Size -->
<xacro:property name="base_x_size" value="0.98740000" />
<xacro:property name="base_y_size" value="0.57090000" />
<xacro:property name="base_z_size" value="0.24750000" />
<!-- Wheel Mounting Positions -->
<xacro:property name="wheelbase" value="0.5120" />
<xacro:property name="track" value="0.5708" />
<xacro:property name="wheel_vertical_offset" value="0.03282" />
<!-- Wheel Properties -->
<xacro:property name="wheel_length" value="0.1143" />
<xacro:property name="wheel_radius" value="0.1651" />
<xacro:property name="M_PI" value="3.14159"/>
<xacro:property name="link_base_mesh" value="base" />
<xacro:property name="link_1_mesh" value="shoulder" />
<xacro:property name="link_2_mesh" value="arm" />
<xacro:property name="link_3_mesh" value="forearm" />
<xacro:property name="link_4_mesh" value="wrist" />
<xacro:property name="link_5_mesh" value="wrist" />
<xacro:property name="link_6_mesh" value="hand_3finger" />
<xacro:property name="link_base_mesh_no" value="0" />
<xacro:property name="link_1_mesh_no" value="1" />
<xacro:property name="link_2_mesh_no" value="2" />
<xacro:property name="link_3_mesh_no" value="3" />
<xacro:property name="link_4_mesh_no" value="4" />
<xacro:property name="link_5_mesh_no" value="4" />
<xacro:property name="link_6_mesh_no" value="55" />
<xacro:property name="joint_base" value="joint_base" />
<xacro:property name="joint_base_type" value="fixed" />
<xacro:property name="joint_base_axis_xyz" value="0 0 0" />
<xacro:property name="joint_base_origin_xyz" value="0.3058 0 0.0065" />
<xacro:property name="joint_base_origin_rpy" value="0 0 0" />
<xacro:property name="joint_1" value="joint_1" />
<xacro:property name="joint_1_type" value="continuous" />
<xacro:property name="joint_1_axis_xyz" value="0 0 1" />
<xacro:property name="joint_1_origin_xyz" value="0 0 0.15675" />
<xacro:property name="joint_1_origin_rpy" value="0 ${J_PI} 0" />
<xacro:property name="joint_1_lower_limit" value="${-2*J_PI}" />
<xacro:property name="joint_1_upper_limit" value="${2*J_PI}" />
<xacro:property name="joint_1_velocity_limit" value="${36*J_PI/180}" />
<xacro:property name="joint_1_torque_limit" value="40" />
<xacro:property name="joint_2" value="joint_2" />
<xacro:property name="joint_2_type" value="revolute" />
<xacro:property name="joint_2_axis_xyz" value="0 0 1" />
<xacro:property name="joint_2_origin_xyz" value="0 0.0016 -0.11875" />
<xacro:property name="joint_2_origin_rpy" value="-${J_PI/2} 0 ${J_PI}" />
<xacro:property name="joint_2_lower_limit" value="${47/180*J_PI}" />
<xacro:property name="joint_2_upper_limit" value="${313/180*J_PI}" />
<xacro:property name="joint_2_velocity_limit" value="${36*J_PI/180}" />
<xacro:property name="joint_2_torque_limit" value="80" />
<xacro:property name="joint_3" value="joint_3" />
<xacro:property name="joint_3_type" value="revolute" />
<xacro:property name="joint_3_axis_xyz" value="0 0 1" />
<xacro:property name="joint_3_origin_xyz" value="0 -0.410 0" />
<xacro:property name="joint_3_origin_rpy" value="0 ${J_PI} 0" />
<xacro:property name="joint_3_lower_limit" value="${19/180*J_PI}" />
<xacro:property name="joint_3_upper_limit" value="${341/180*J_PI}" />
<xacro:property name="joint_3_velocity_limit" value="${36*J_PI/180}" />
<xacro:property name="joint_3_torque_limit" value="40" />
<xacro:property name="joint_4" value="joint_4" />
<xacro:property name="joint_4_type" value="continuous" />
<xacro:property name="joint_4_axis_xyz" value="0 0 1" />
<xacro:property name="joint_4_origin_xyz" value="0 0.2073 -0.0114" />
<xacro:property name="joint_4_origin_rpy" value="-${J_PI/2} 0 ${J_PI}" />
<xacro:property name="joint_4_lower_limit" value="${-2*J_PI}" />
<xacro:property name="joint_4_upper_limit" value="${2*J_PI}" />
<xacro:property name="joint_4_velocity_limit" value="${48*J_PI/180}" />
<xacro:property name="joint_4_torque_limit" value="20" />
<xacro:property name="joint_5" value="joint_5" />
<xacro:property name="joint_5_type" value="continuous" />
<xacro:property name="joint_5_axis_xyz" value="0 0 1" />
<xacro:property name="joint_5_origin_xyz" value="0 -0.03703 -0.06414" />
<xacro:property name="joint_5_origin_rpy" value="${J_PI/3} 0 ${J_PI}" />
<xacro:property name="joint_5_lower_limit" value="${-2*J_PI}" />
<xacro:property name="joint_5_upper_limit" value="${2*J_PI}" />
<xacro:property name="joint_5_velocity_limit" value="${48*J_PI/180}" />
<xacro:property name="joint_5_torque_limit" value="20" />
<xacro:property name="joint_6" value="joint_6" />
<xacro:property name="joint_6_type" value="continuous" />
<xacro:property name="joint_6_axis_xyz" value="0 0 1" />
<xacro:property name="joint_6_origin_xyz" value="0 -0.03703 -0.06414" />
<xacro:property name="joint_6_origin_rpy" value="${J_PI/3} 0 ${J_PI}" />
<xacro:property name="joint_6_lower_limit" value="${-2*J_PI}" />
<xacro:property name="joint_6_upper_limit" value="${2*J_PI}" />
<xacro:property name="joint_6_velocity_limit" value="${48*J_PI/180}" />
<xacro:property name="joint_6_torque_limit" value="20" />
<xacro:property name="joint_end_effector" value="end_effector_offset" />
<xacro:property name="joint_end_effector_type" value="fixed" />
<xacro:property name="joint_end_effector_axis_xyz" value="0 0 0" />
<xacro:property name="joint_end_effector_origin_xyz" value="0 0 -0.1600" />
<xacro:property name="joint_end_effector_origin_rpy" value="${J_PI} 0 ${J_PI/2}" />
<!-- Included URDF/XACRO Files -->
<xacro:include filename="$(find my_two_description)/urdf/decorations.urdf.xacro" />
<xacro:include filename="$(find my_two_description)/urdf/wheel.urdf.xacro" />
<xacro:include filename="$(find my_two_description)/urdf/kinova_common.xacro" />
<xacro:include filename="$(find my_two_description)/urdf/kinova_finger_set.xacro" />
<!-- Base link is the center of the robot's bottom plate -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://my_two_description/meshes/base_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="${( husky_front_bumper_extend - husky_rear_bumper_extend ) / 2.0} 0 ${base_z_size/4}" rpy="0 0 0" />
<geometry>
<box size="${ base_x_size + husky_front_bumper_extend + husky_rear_bumper_extend } ${base_y_size} ${base_z_size/2}"/>
</geometry>
</collision>
<collision>
<origin xyz="0 0 ${base_z_size*3/4-0.01}" rpy="0 0 0" />
<geometry>
<box size="${base_x_size*4/5} ${base_y_size} ${base_z_size/2-0.02}"/>
</geometry>
</collision>
</link>
<!-- Base footprint is on the ground under the robot -->
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
<parent link="base_link" />
<child link="base_footprint" />
</joint>
<!-- Interial link stores the robot's inertial information -->
<link name="inertial_link">
<inertial>
<mass value="46.034" />
<origin xyz="-0.00065 -0.085 0.062" />
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" />
</inertial>
</link>
<joint name="inertial_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="inertial_link" />
</joint>
<!-- Husky wheel macros -->
<xacro:husky_wheel wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_wheel wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:husky_wheel>
<xacro:husky_decorate />
<xacro:macro name="j2n6s300" params="base_parent prefix:=j2n6s300">
<xacro:kinova_armlink link_name="${prefix}_link_base" link_mesh="${link_base_mesh}" mesh_no="${link_base_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_base" type="${joint_base_type}" parent="${base_parent}" child="${prefix}_link_base" joint_axis_xyz="${joint_base_axis_xyz}" joint_origin_xyz="${joint_base_origin_xyz}" joint_origin_rpy="${joint_base_origin_rpy}" joint_lower_limit="0" joint_upper_limit="0" joint_velocity_limit="0" joint_torque_limit="0" fixed="true"/>
<xacro:kinova_armlink link_name="${prefix}_link_1" link_mesh="${link_1_mesh}" use_ring_mesh="true" mesh_no="${link_1_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_1" type="${joint_1_type}" parent="${prefix}_link_base" child="${prefix}_link_1" joint_axis_xyz="${joint_1_axis_xyz}" joint_origin_xyz="${joint_1_origin_xyz}" joint_origin_rpy="${joint_1_origin_rpy}" joint_lower_limit="${joint_1_lower_limit}" joint_upper_limit="${joint_1_upper_limit}" joint_velocity_limit="${joint_1_velocity_limit}" joint_torque_limit="${joint_1_torque_limit}"/>
<xacro:kinova_armlink link_name="${prefix}_link_2" link_mesh="${link_2_mesh}" use_ring_mesh="true" mesh_no="${link_2_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_2" type="${joint_2_type}" parent="${prefix}_link_1" child="${prefix}_link_2" joint_axis_xyz="${joint_2_axis_xyz}" joint_origin_xyz="${joint_2_origin_xyz}" joint_origin_rpy="${joint_2_origin_rpy}" joint_lower_limit="${joint_2_lower_limit}" joint_upper_limit="${joint_2_upper_limit}" joint_velocity_limit="${joint_2_velocity_limit}" joint_torque_limit="${joint_2_torque_limit}"/>
<xacro:kinova_armlink link_name="${prefix}_link_3" link_mesh="${link_3_mesh}" use_ring_mesh="true" mesh_no="${link_3_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_3" type="${joint_3_type}" parent="${prefix}_link_2" child="${prefix}_link_3" joint_axis_xyz="${joint_3_axis_xyz}" joint_origin_xyz="${joint_3_origin_xyz}" joint_origin_rpy="${joint_3_origin_rpy}" joint_lower_limit="${joint_3_lower_limit}" joint_upper_limit="${joint_3_upper_limit}" joint_velocity_limit="${joint_3_velocity_limit}" joint_torque_limit="${joint_3_torque_limit}"/>
<xacro:kinova_armlink link_name="${prefix}_link_4" link_mesh="${link_4_mesh}" use_ring_mesh="true" ring_mesh="ring_small" mesh_no="${link_4_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_4" type="${joint_4_type}" parent="${prefix}_link_3" child="${prefix}_link_4" joint_axis_xyz="${joint_4_axis_xyz}" joint_origin_xyz="${joint_4_origin_xyz}" joint_origin_rpy="${joint_4_origin_rpy}" joint_lower_limit="${joint_4_lower_limit}" joint_upper_limit="${joint_4_upper_limit}" joint_velocity_limit="${joint_4_velocity_limit}" joint_torque_limit="${joint_4_torque_limit}"/>
<xacro:kinova_armlink link_name="${prefix}_link_5" link_mesh="${link_5_mesh}" use_ring_mesh="true" ring_mesh="ring_small" mesh_no="${link_5_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_5" type="${joint_5_type}" parent="${prefix}_link_4" child="${prefix}_link_5" joint_axis_xyz="${joint_5_axis_xyz}" joint_origin_xyz="${joint_5_origin_xyz}" joint_origin_rpy="${joint_5_origin_rpy}" joint_lower_limit="${joint_5_lower_limit}" joint_upper_limit="${joint_5_upper_limit}" joint_velocity_limit="${joint_5_velocity_limit}" joint_torque_limit="${joint_5_torque_limit}"/>
<xacro:kinova_armlink link_name="${prefix}_link_6" link_mesh="${link_6_mesh}" use_ring_mesh="true" ring_mesh="ring_small" mesh_no="${link_6_mesh_no}"/>
<xacro:kinova_armjoint joint_name="${prefix}_joint_6" type="${joint_6_type}" parent="${prefix}_link_5" child="${prefix}_link_6" joint_axis_xyz="${joint_6_axis_xyz}" joint_origin_xyz="${joint_6_origin_xyz}" joint_origin_rpy="${joint_6_origin_rpy}" joint_lower_limit="${joint_6_lower_limit}" joint_upper_limit="${joint_6_upper_limit}" joint_velocity_limit="${joint_6_velocity_limit}" joint_torque_limit="${joint_6_torque_limit}"/>
<xacro:kinova_virtual_link link_name="${prefix}_end_effector"/>
<xacro:kinova_virtual_joint joint_name="${prefix}_joint_end_effector" type="${joint_end_effector_type}" parent="${prefix}_link_6" child="${prefix}_end_effector" joint_axis_xyz="${joint_end_effector_axis_xyz}" joint_origin_xyz="${joint_end_effector_origin_xyz}" joint_origin_rpy="${joint_end_effector_origin_rpy}" joint_lower_limit="0" joint_upper_limit="0"/>
<xacro:kinova_3fingers link_hand="${prefix}_link_6" prefix="${prefix}_"/>
</xacro:macro>
<xacro:j2n6s300 base_parent="top_plate_link" />
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
</robot>
2.husky_wheel宏在 wheel.urdf.xacro中定义
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="husky_wheel">
<xacro:macro name="husky_wheel" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="2.637" />
<origin xyz="0 0 0" />
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.04411" iyz="0" izz="0.02467" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://my_two_description/meshes/wheel.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 1 0" rpy="0 0 0" />
</joint>
<transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
</robot>
3.kinova_armlink宏、kinova_armjoint宏、kinova_virtual_link宏、kinova_virtual_joint宏在kinova_common.xacro中定义
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="kinova_common">
<xacro:include filename="$(find my_two_description)/urdf/kinova_inertial.xacro" />
<xacro:property name="J_PI" value="3.1415926535897931" />
<xacro:macro name="kinova_armlink" params="link_name link_mesh ring_mesh:=ring_big use_ring_mesh:=false mesh_no">
<link name="${link_name}">
<visual>
<geometry>
<mesh
filename="package://my_two_description/meshes/${link_mesh}.dae"/>
</geometry>
<material name="carbon_fiber">
<color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<!-- Adding ring to the model -->
<xacro:if value="${use_ring_mesh}">
<visual>
<geometry>
<mesh
filename="package://my_two_description/meshes/${ring_mesh}.dae"/>
</geometry>
</visual>
</xacro:if>
<collision>
<geometry>
<mesh
filename="package://my_two_description/meshes/${link_mesh}.dae"/>
</geometry>
</collision>
<xacro:kinova_inertial mesh_no="${mesh_no}"/>
</link>
</xacro:macro>
<xacro:macro name="kinova_armjoint" params="joint_name type parent child joint_axis_xyz joint_origin_xyz joint_origin_rpy joint_lower_limit joint_upper_limit joint_velocity_limit joint_torque_limit fixed:=false">
<joint name="${joint_name}" type="${type}">
<parent link="${parent}"/>
<child link="${child}"/>
<axis xyz="${joint_axis_xyz}"/>
<limit effort="${joint_torque_limit}" velocity="${joint_velocity_limit}" lower="${joint_lower_limit}" upper="${joint_upper_limit}"/>
<origin xyz="${joint_origin_xyz}" rpy="${joint_origin_rpy}"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
<xacro:unless value="${fixed}">
<transmission name="${joint_name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${joint_name}_actuator">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>160</mechanicalReduction>
</actuator>
</transmission>
<!--For torque sensing in simulation-->
<gazebo reference="${joint_name}">
<provideFeedback>true</provideFeedback>
</gazebo>
<gazebo>
<plugin name="ft_sensor" filename="libgazebo_ros_ft_sensor.so">
<updateRate>30.0</updateRate>
<topicName>${joint_name}_ft_sensor_topic</topicName>
<jointName>${joint_name}</jointName>
</plugin>
</gazebo>
</xacro:unless>
</xacro:macro>
<xacro:macro name="kinova_virtual_link" params="link_name">
<link name="${link_name}"/>
</xacro:macro>
<xacro:macro name="kinova_virtual_joint" params="joint_name type parent child joint_axis_xyz joint_origin_xyz joint_origin_rpy joint_lower_limit joint_upper_limit">
<joint name="${joint_name}" type="${type}">
<parent link="${parent}"/>
<child link="${child}"/>
<axis xyz="${joint_axis_xyz}"/>
<limit effort="2000" velocity="1" lower="${joint_lower_limit}" upper="${joint_upper_limit}"/>
<origin xyz="${joint_origin_xyz}" rpy="${joint_origin_rpy}"/>
</joint>
</xacro:macro>
<xacro:macro name="kinova_finger" params="prefix finger_number hand finger_origin_xyz finger_origin_rpy">
<xacro:kinova_armlink link_name="${prefix}link_finger_${finger_number}" link_mesh="finger_proximal" mesh_no="57"/>
<joint name="${prefix}joint_finger_${finger_number}" type="revolute">
<parent link="${hand}"/>
<child link="${prefix}link_finger_${finger_number}"/>
<axis xyz="0 0 1"/>
<origin xyz="${finger_origin_xyz}" rpy="${finger_origin_rpy}"/>
<limit lower="0" upper="1.51" effort="2" velocity="1"/>
</joint>
<transmission name="${prefix}joint_finger_${finger_number}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint_finger_${finger_number}">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}joint_finger_${finger_number}_actuator">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<xacro:kinova_armlink link_name="${prefix}link_finger_tip_${finger_number}" link_mesh="finger_distal" mesh_no="58"/>
<joint name="${prefix}joint_finger_tip_${finger_number}" type="revolute">
<parent link="${prefix}link_finger_${finger_number}"/>
<child link="${prefix}link_finger_tip_${finger_number}"/>
<axis xyz="0 0 1"/>
<origin xyz="0.044 -0.003 0" rpy="0 0 0"/>
<limit lower="0" upper="2" effort="2" velocity="1"/>
</joint>
<transmission name="${prefix}joint_finger_tip_${finger_number}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}joint_finger_tip_${finger_number}">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}joint_finger_tip_${finger_number}_actuator">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
</robot>
4.kinova_3fingers宏在kinova_finger_set.xacro中定义
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="kinova_finger">
<xacro:include filename="$(find my_two_description)/urdf/kinova_common.xacro" />
<xacro:macro name="kinova_3fingers" params="link_hand prefix">
<!-- finger1 Rot := Ry((1/2)*Pi) . Rx(12.1*((1/180)*Pi)+Pi) . Rz(-52.8*((1/180)*Pi)) -->
<xacro:kinova_finger prefix="${prefix}" finger_number="1" hand="${link_hand}" finger_origin_xyz="0.00279 0.03126 -0.11467" finger_origin_rpy="-1.570796327 .649262481663582 1.35961148639407"/>
<!-- finger2 Rot := Ry((1/2)*Pi) . Rx(10.58*((1/180)*Pi)) . Rz(-52.8*((1/180)*Pi)) -->
<xacro:kinova_finger prefix="${prefix}" finger_number="2" hand="${link_hand}" finger_origin_xyz="0.02226 -0.02707 -0.11482" finger_origin_rpy="-1.570796327 .649262481663582 -1.38614049188413"/>
<!-- finger3 Rot := Ry((1/2)*Pi) . Rx(-10.58*((1/180)*Pi)) . Rz(-52.8*((1/180)*Pi)) -->
<xacro:kinova_finger prefix="${prefix}" finger_number="3" hand="${link_hand}" finger_origin_xyz="-0.02226 -0.02707 -0.11482" finger_origin_rpy="-1.570796327 .649262481663582 -1.75545216211587"/>
</xacro:macro>
<xacro:macro name="kinova_2fingers" params="link_hand prefix">
<!-- finger1 Rot := Ry((1/2)*Pi) . Rx(Pi) . Rz(-52.8*((1/180)*Pi)) -->
<xacro:kinova_finger prefix="${prefix}" finger_number="1" hand="${link_hand}" finger_origin_xyz="-0.0025 0.03095 -0.11482" finger_origin_rpy="-1.570796327 .649262481663582 1.57079632679490"/>
<!-- finger2 Rot := Ry((1/2)*Pi) . Rz(-52.8*((1/180)*Pi)) -->
<xacro:kinova_finger prefix="${prefix}" finger_number="2" hand="${link_hand}" finger_origin_xyz="-0.0025 -0.03095 -0.11482" finger_origin_rpy="-1.570796327 .649262481663582 -1.57079632679490"/>
</xacro:macro>
</robot>
5.kinova_finger宏在kinova_common.xacro中定义
6.display_husky_kinova.launch
<launch>
<!-- 设置机器人模型路径参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find my_two_description)/urdf/husky_kinova.xacro'" />
<arg name="gui" default="true" />
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- 运行rviz可视化界面 -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find my_two_description)/config/husky_kinova.rviz" required="true" />
</launch>
注意这里设置机器人模型路径参数时,需要将.xacro文件转换成.urdf文件,这里就是之前解析不了属性标签的原因所在。
编译工作空间后在rviz中查看:
7.husky_kinova_empty_world.launch
<?xml version="1.0"?>
<launch>
<!-- 设置launch文件的参数 -->
<arg name="paused" default="true"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find my_two_description)/urdf/husky_kinova.xacro'" />
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>
<!-- 在gazebo中加载机器人模型-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model husky_kinova -param robot_description
-J j2n6s300_joint_1 0.0
-J j2n6s300_joint_2 2.9
-J j2n6s300_joint_3 0.0
-J j2n6s300_joint_4 1.3
-J j2n6s300_joint_5 -2.07
-J j2n6s300_joint_6 1.4
-J j2n6s300_joint_7 0.0
-J j2n6s300_joint_finger_1 1.0
-J j2n6s300_joint_finger_2 1.0
-J j2n6s300_joint_finger_3 1.0" />
</launch>
在gazebo中查看:
这里之所以这样显示,是因为启动gazebo时启用了物理暂停,此时保持的是最初始的状态。车轮埋在地面以下是因为在编写husky模型时,底盘定位在了z=0的高度,应该没有影响,当启用gazebo仿真时,会进入物理仿真状态,机械臂在重力作用下耷拉下来。