Compare commits

...
Sign in to create a new pull request.

3 commits

4 changed files with 18 additions and 9 deletions

View file

@ -3,7 +3,12 @@
gz_type_name: "gz.msgs.Clock" gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS direction: GZ_TO_ROS
- topic_name: "/rgbd_camera/image" - topic_name: "/inner_rgbd_camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS
- topic_name: "/outer_rgbd_camera/image"
ros_type_name: "sensor_msgs/msg/Image" ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image" gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS direction: GZ_TO_ROS

View file

@ -251,8 +251,12 @@
</xacro:simple_parallel_gripper> </xacro:simple_parallel_gripper>
<xacro:rgbd parent="wrist3_Link" tf_prefix=""> <xacro:rgbd parent="wrist3_Link" tf_prefix="inner_">
<origin xyz="0.0 0.05 0.04" rpy="0.0 -1.47 -1.57" /> <origin xyz="0.0 0.05 0.0" rpy="0.0 -1.47 -1.57" />
</xacro:rgbd>
<xacro:rgbd parent="base_link" tf_prefix="outer_">
<origin xyz="0.62179261445999146 -0.83430188894271851 0.85204130411148071" rpy="0.00 0.608 1.934" />
</xacro:rgbd> </xacro:rgbd>
<xacro:aubo_ros2_control hardware="${hardware}" robot_ip="${robot_ip}" /> <xacro:aubo_ros2_control hardware="${hardware}" robot_ip="${robot_ip}" />

View file

@ -30,8 +30,8 @@
<camera> <camera>
<horizontal_fov>1.047</horizontal_fov> <horizontal_fov>1.047</horizontal_fov>
<image> <image>
<width>1920</width> <width>640</width>
<height>1080</height> <height>480</height>
</image> </image>
<clip> <clip>
<near>0.1</near> <near>0.1</near>

View file

@ -110,8 +110,8 @@
<collision name="cylinder_collision"> <collision name="cylinder_collision">
<geometry> <geometry>
<cylinder> <cylinder>
<radius>0.03</radius> <radius>0.01</radius>
<length>0.1</length> <length>0.05</length>
</cylinder> </cylinder>
</geometry> </geometry>
<surface> <surface>
@ -133,8 +133,8 @@
<visual name="cylinder_visual"> <visual name="cylinder_visual">
<geometry> <geometry>
<cylinder> <cylinder>
<radius>0.03</radius> <radius>0.01</radius>
<length>0.1</length> <length>0.05</length>
</cylinder> </cylinder>
</geometry> </geometry>
<material> <material>