Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions eager_core/src/eager_core/render_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,11 @@ def render(self):
if self.image_ros is None:
return
try:
cv_image = self.bridge.imgmsg_to_cv2(self.image_ros)
# Related issue: https://github.com/ros-perception/vision_opencv/issues/207
cv_image = np.frombuffer(self.image_ros.data, dtype=np.uint8).reshape(self.image_ros.height, self.image_ros.width, -1)
cv_image = cv2.cvtColor(cv_image, cv2.COLOR_RGB2BGR)
# cv_image = np.frombuffer(self.image_ros.data, dtype=np.uint8).reshape(self.image_ros.height, self.image_ros.width, -1)
if not self.image_ros.encoding == 'bgra8':
cv_image = cv2.cvtColor(cv_image, cv2.COLOR_RGB2BGR)
except CvBridgeError as e:
print(e)
return
Expand Down
2 changes: 1 addition & 1 deletion eager_robots/eager_robot_vx300s/config/vx300s.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ actuators:
states:
joint_pos:
type: boxf32
high: [3.14158, 0.628315, 1.605702, 3.14158, 2.23402, 3.14158]
high: [3.14158, 0.628315, 0.802851, 3.14158, 2.23402, 3.14158]
low: [-3.14158, -0.92502, -1.76278, -3.14158, -1.86750, -3.14158]
joint_vel:
type: boxf32
Expand Down
455 changes: 455 additions & 0 deletions eager_robots/eager_robot_vx300s/vx300s.urdf

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@ sensors:
type: boxu8
high: 255
low: 0
shape: [1024, 544, 4]
shape: [544, 1024, 4]
camera_left:
type: boxu8
high: 255
low: 0
shape: [1024, 544, 4]
shape: [544, 1024, 4]

webots:
node_type_name: MultiSenseS21
Expand All @@ -27,10 +27,12 @@ webots:
- MultiSense_S21_left_camera

pybullet:
urdf:
xacro: $(find eager_sensor_multisense_s21)/urdf/multisense_s21.urdf.xacro
urdf_name: multisense_s21
sensors:
camera_right:
type: camera_rgbd
optical_frame_link: right_camera_optical_frame
names: [MultiSense_S21_right_camera]
intrinsic:
fov: 80.21 # (deg)
Expand All @@ -44,6 +46,7 @@ pybullet:

camera_left:
type: camera_rgbd
optical_frame_link: left_camera_optical_frame
names: [MultiSense_S21_left_camera]
intrinsic:
fov: 80.21 # (deg)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<!-- Robot state publisher -->
<group ns="$(arg ns)">
<param name="robot_description"
command="$(find xacro)/xacro '$(find eager_sensor_multisense_s21)/urdf/multisense_s21.urdf.xacro'"/>
command="$(find xacro)/xacro '$(find eager_sensor_multisense_s21)/urdf/multisense_s21.urdf.xacro' gazebo:=true"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
</node>
Expand Down
88 changes: 88 additions & 0 deletions eager_sensors/eager_sensor_multisense_s21/multisense_s21.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/jelle/eager_ws/src/eager_sensor_multisense_s21/urdf/multisense_s21.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="multisense">
<link name="world"/>
<joint name="dummy_joint" type="fixed">
<origin xyz="0.0 0.0 0.0"/>
<parent link="world"/>
<child link="head"/>
</joint>
<link name="head">
<inertial>
<origin rpy="0 0 0" xyz="-0.075493 3.3383E-05 0.02774"/>
<mass value="1.4199"/>
<inertia ixx="0.0039688" ixy="-1.5797E-06" ixz="-0.00089293" iyy="0.0041178" iyz="-6.8415E-07" izz="0.0035243"/>
</inertial>
<visual>
<origin rpy="1.57079632679 0 1.57079632679" xyz="0 0 0"/>
<geometry>
<mesh filename="/home/jelle/eager_ws/src/eager_sensor_multisense_s21/meshes/multisense_s21.dae"/>
</geometry>
<material name="">
<color rgba="0.9098 0.44314 0.031373 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.0503 0 -0.00195"/>
<geometry>
<box size="0.1311 0.12 0.0591"/>
</geometry>
</collision>
</link>
<!-- Note the origin of model is 37.3854mm from the rear mounting plane
in the x axis -->
<joint name="left_camera_joint" type="fixed">
<origin xyz="0.07 0.105 0.0"/>
<parent link="head"/>
<child link="left_camera_frame"/>
</joint>
<link name="left_camera_frame"/>
<joint name="right_camera_joint" type="fixed">
<origin xyz="0.07 -0.105 0.0"/>
<parent link="head"/>
<child link="right_camera_frame"/>
</joint>
<link name="right_camera_frame"/>
<joint name="left_camera_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0.0052046 0 0"/>
<parent link="left_camera_frame"/>
<child link="left_camera_optical_frame"/>
</joint>
<link name="left_camera_optical_frame"/>
<joint name="right_camera_optical_joint" type="fixed">
<origin rpy="-1.57079632679 0.0 -1.57079632679" xyz="0.0052046 0 0"/>
<parent link="right_camera_frame"/>
<child link="right_camera_optical_frame"/>
</joint>
<link name="right_camera_optical_frame"/>
<joint name="top_left_rear_mount_joint" type="fixed">
<origin rpy="0 0 3.14159" xyz="-0.0373854 0.1 0.014"/>
<parent link="head"/>
<child link="top_left_rear_mount"/>
</joint>
<link name="top_left_rear_mount"/>
<!--Note the locations of the accel/mag and gyro differ from those shown
in CAD. The S21 firmware switches axis on the accel/mag and gyro to
match the S7/S7S/SL MultiSense configurations -->
<joint name="accel_joint" type="fixed">
<origin rpy="0.0 1.57079632679 0.0" xyz="0.0045 0.029 -0.0135"/>
<parent link="head"/>
<child link="accel"/>
</joint>
<link name="accel"/>
<joint name="mag_joint" type="fixed">
<origin rpy="0.0 1.57079632679 0.0" xyz="0.0045 0.029 -0.0135"/>
<parent link="head"/>
<child link="mag"/>
</joint>
<link name="mag"/>
<joint name="gyro_joint" type="fixed">
<origin rpy="-1.57079632679 0 -1.57079632679" xyz="-0.00219539 0.03758 -0.014"/>
<parent link="head"/>
<child link="gyro"/>
</joint>
<link name="gyro"/>
</robot>
Original file line number Diff line number Diff line change
@@ -1,9 +1,17 @@
<robot name="multisense" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="gazebo" default="false"/>
<xacro:property name="load_gazebo" value="$(arg gazebo)"/>

<!-- import the camera -->
<xacro:include filename="$(find eager_sensor_multisense_s21)/urdf/camera.gazebo.xacro" />
<xacro:include filename="$(find eager_sensor_multisense_s21)/urdf/s21.urdf.xacro" />

<link name="world"/>

<!-- camera -->
<xacro:my_camera parent="world"/>
<xacro:sensor_s21 parent="world"/>

<xacro:if value="${load_gazebo}">
<xacro:include filename="$(find eager_sensor_multisense_s21)/urdf/s21.gazebo.xacro" />
<xacro:s21_gazebo/>
</xacro:if>
</robot>
Original file line number Diff line number Diff line change
@@ -1,108 +1,7 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="my_camera" params="parent">

<joint name="dummy_joint" type="fixed">
<origin xyz="0.0 0.0 0.0"/>
<parent link="${parent}"/>
<child link="head"/>
</joint>

<link name="head">
<inertial>
<origin xyz="-0.075493 3.3383E-05 0.02774" rpy="0 0 0" />
<mass value="1.4199" />
<inertia iyy="0.0041178" ixy="-1.5797E-06" iyz="-6.8415E-07" ixx="0.0039688" ixz="-0.00089293" izz="0.0035243" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.57079632679 0 1.57079632679" />
<geometry>
<mesh filename="package://eager_sensor_multisense_s21/meshes/multisense_s21.dae"/>
</geometry>
<material name="">
<color rgba="0.9098 0.44314 0.031373 1" />
</material>
</visual>
<collision>
<origin xyz="-0.0503 0 -0.00195" rpy="0 0 0" />
<geometry>
<box size="0.1311 0.12 0.0591"/>
</geometry>
</collision>
</link>

<!-- Note the origin of model is 37.3854mm from the rear mounting plane
in the x axis -->

<joint name="left_camera_joint" type="fixed">
<origin xyz="0.07 0.105 0.0"/>
<parent link="head"/>
<child link="left_camera_frame"/>
</joint>

<link name="left_camera_frame"/>

<joint name="right_camera_joint" type="fixed">
<origin xyz="0.07 -0.105 0.0"/>
<parent link="head"/>
<child link="right_camera_frame"/>
</joint>

<link name="right_camera_frame"/>

<joint name="left_camera_optical_joint" type="fixed">
<origin xyz="0.0052046 0 0" rpy="-1.57079632679 0.0 -1.57079632679"/>
<parent link="left_camera_frame"/>
<child link="left_camera_optical_frame"/>
</joint>

<link name="left_camera_optical_frame"/>

<joint name="right_camera_optical_joint" type="fixed">
<origin xyz="0.0052046 0 0" rpy="-1.57079632679 0.0 -1.57079632679"/>
<parent link="right_camera_frame"/>
<child link="right_camera_optical_frame"/>
</joint>

<link name="right_camera_optical_frame"/>

<joint name="top_left_rear_mount_joint" type="fixed">
<origin xyz="-0.0373854 0.1 0.014" rpy="0 0 3.14159"/>
<parent link="head"/>
<child link="top_left_rear_mount"/>
</joint>

<link name="top_left_rear_mount"/>

<!--Note the locations of the accel/mag and gyro differ from those shown
in CAD. The S21 firmware switches axis on the accel/mag and gyro to
match the S7/S7S/SL MultiSense configurations -->

<joint name="accel_joint" type="fixed">
<origin xyz="0.0045 0.029 -0.0135" rpy="0.0 1.57079632679 0.0"/>
<parent link="head"/>
<child link="accel"/>
</joint>

<link name="accel"/>

<joint name="mag_joint" type="fixed">
<origin xyz="0.0045 0.029 -0.0135" rpy="0.0 1.57079632679 0.0"/>
<parent link="head"/>
<child link="mag"/>
</joint>

<link name="mag"/>

<joint name="gyro_joint" type="fixed">
<origin xyz="-0.00219539 0.03758 -0.014" rpy="-1.57079632679 0 -1.57079632679"/>
<parent link="head"/>
<child link="gyro"/>
</joint>

<link name="gyro"/>

<xacro:macro name="s21_gazebo">
<gazebo reference="head">
<material>Gazebo/DarkGrey </material>
</gazebo>
Expand Down
106 changes: 106 additions & 0 deletions eager_sensors/eager_sensor_multisense_s21/urdf/s21.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="sensor_s21" params="parent">

<joint name="dummy_joint" type="fixed">
<origin xyz="0.0 0.0 0.0"/>
<parent link="${parent}"/>
<child link="head"/>
</joint>

<link name="head">
<inertial>
<origin xyz="-0.075493 3.3383E-05 0.02774" rpy="0 0 0" />
<mass value="1.4199" />
<inertia iyy="0.0041178" ixy="-1.5797E-06" iyz="-6.8415E-07" ixx="0.0039688" ixz="-0.00089293" izz="0.0035243" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="1.57079632679 0 1.57079632679" />
<geometry>
<mesh filename="package://eager_sensor_multisense_s21/meshes/multisense_s21.dae"/>
</geometry>
<material name="">
<color rgba="0.9098 0.44314 0.031373 1" />
</material>
</visual>
<collision>
<origin xyz="-0.0503 0 -0.00195" rpy="0 0 0" />
<geometry>
<box size="0.1311 0.12 0.0591"/>
</geometry>
</collision>
</link>

<!-- Note the origin of model is 37.3854mm from the rear mounting plane
in the x axis -->

<joint name="left_camera_joint" type="fixed">
<origin xyz="0.07 0.105 0.0"/>
<parent link="head"/>
<child link="left_camera_frame"/>
</joint>

<link name="left_camera_frame"/>

<joint name="right_camera_joint" type="fixed">
<origin xyz="0.07 -0.105 0.0"/>
<parent link="head"/>
<child link="right_camera_frame"/>
</joint>

<link name="right_camera_frame"/>

<joint name="left_camera_optical_joint" type="fixed">
<origin xyz="0.0052046 0 0" rpy="-1.57079632679 0.0 -1.57079632679"/>
<parent link="left_camera_frame"/>
<child link="left_camera_optical_frame"/>
</joint>

<link name="left_camera_optical_frame"/>

<joint name="right_camera_optical_joint" type="fixed">
<origin xyz="0.0052046 0 0" rpy="-1.57079632679 0.0 -1.57079632679"/>
<parent link="right_camera_frame"/>
<child link="right_camera_optical_frame"/>
</joint>

<link name="right_camera_optical_frame"/>

<joint name="top_left_rear_mount_joint" type="fixed">
<origin xyz="-0.0373854 0.1 0.014" rpy="0 0 3.14159"/>
<parent link="head"/>
<child link="top_left_rear_mount"/>
</joint>

<link name="top_left_rear_mount"/>

<!--Note the locations of the accel/mag and gyro differ from those shown
in CAD. The S21 firmware switches axis on the accel/mag and gyro to
match the S7/S7S/SL MultiSense configurations -->

<joint name="accel_joint" type="fixed">
<origin xyz="0.0045 0.029 -0.0135" rpy="0.0 1.57079632679 0.0"/>
<parent link="head"/>
<child link="accel"/>
</joint>

<link name="accel"/>

<joint name="mag_joint" type="fixed">
<origin xyz="0.0045 0.029 -0.0135" rpy="0.0 1.57079632679 0.0"/>
<parent link="head"/>
<child link="mag"/>
</joint>

<link name="mag"/>

<joint name="gyro_joint" type="fixed">
<origin xyz="-0.00219539 0.03758 -0.014" rpy="-1.57079632679 0 -1.57079632679"/>
<parent link="head"/>
<child link="gyro"/>
</joint>

<link name="gyro"/>
</xacro:macro>
</robot>
Loading