0. 下载链接
realsense-ros:https://github.com/IntelRealSense/realsense-ros
1. 查看模型
roslaunch realsense2_description view_d435_model.launch
2. 将相机添加到 UR3 模型中
2.1 新建 ur3_ft_gripper140_realsensed435_robot.urdf.xacro
修改 ur3_ft_gripper140_realsensed435_robot.urdf.xacro文件中的内容,添加下面代码的最后一段(这段代码来自realsense2_description/urdf/test_d435_camera.urdf.xacro):
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro"
name="ur3" >
<xacro:arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface"/>
<!-- common stuff -->
<xacro:include filename="$(find ur_description)/urdf/common.gazebo.xacro" />
<!-- ur3 -->
<xacro:include filename="$(find ur_description)/urdf/ur3.urdf.xacro" />
<!-- arm -->
<xacro:ur3_robot prefix="" joint_limited="false"
transmission_hw_interface="$(arg transmission_hw_interface)"
/>
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
<!-- Add robotiq_ft300-->
<xacro:include filename="$(find robotiq_ft_sensor)/urdf/robotiq_ft300.urdf.xacro" />
<xacro:robotiq_ft300 parent="tool0" prefix="">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:robotiq_ft300>
<!-- Add robotiq arg2f140-->
<!-- Copy from robotiq_arg2f_140_model.xacro -->
<xacro:include filename="$(find robotiq_2f_140_gripper_visualization)/urdf/robotiq_arg2f_140_model_macro.xacro" />
<xacro:robotiq_arg2f_140 prefix=""/>
<!-- Link to the end of ft300 -->
<joint name="ft_gripper_joint" type="fixed">
<parent link="robotiq_ft_frame_id"/>
<child link="robotiq_arg2f_base_link"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<!-- Add realsense d435 -->
<xacro:arg name="use_nominal_extrinsics" default="false"/>
<xacro:arg name="add_plug" default="false" />
<xacro:arg name="use_mesh" default="true" />
<xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
<xacro:sensor_d435 parent="world" use_nominal_extrinsics="$(arg use_nominal_extrinsics)" add_plug="$(arg add_plug)" use_mesh="$(arg use_mesh)">
<origin xyz="0.4 0 1" rpy="0 1.57 0"/>
</xacro:sensor_d435>
</robot>
添加后的效果如下:
2.2 新建文件ur3_ft_gripper140_realsensed435_upload.launch
- 复制
ur3_ft_gripper140_upload.launch
的内容,并修改得到: -
<?xml version="1.0"?> <launch> <arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." /> <arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" /> <param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_ft_gripper140_realsensed435_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" /> <param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" /> </launch>
- 修改后效果如下:
-
2.3 新建文件
view_ur3_ft_gripper140_realsensed435.launch
- 复制
view_ur3_ft_gripper140_realsensed435.launch
中的内容,修改后得到: -
<?xml version="1.0"?> <launch> <include file="$(find ur_description)/launch/ur3_ft_gripper140_realsensed435_upload.launch"/> <node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" > <param name="use_gui" value="true"/> </node> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find ur_description)/cfg/view_robot.rviz" required="true" /> </launch>
- 修改后效果如下:
-
2.4 查看最终效果
-
roslaunch ur_description view_ur3_ft_gripper140_realsensed435.launch
- 复制
评论(0)
您还未登录,请登录后发表或查看评论