Commit 462a556a authored by Simon Markus Haller-Seeber's avatar Simon Markus Haller-Seeber
Browse files

Added Documentation. Finalized ARM URDF, MiniBOt URDF. Added display launchfile

parent 53c430e6
......@@ -161,7 +161,7 @@
<xacro:insert_block name="negligible_inertia"/>
</inertial>
<visual>
<origin xyz="0.016 0.0127 -0.0128" rpy="0 0 0"/>
<origin xyz="0.0135 0.0127 -0.0128" rpy="0 0 0"/>
<geometry>
<mesh filename="package://lss_4dof_description/meshes/Link_4.stl" scale="0.001 0.001 0.001" />
</geometry>
......
<?xml version="1.0"?>
<!--
License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 Intel Corporation. All Rights Reserved
This is the URDF model for the Intel RealSense 430 camera, in it's
aluminum peripherial evaluation case.
-->
<robot name="sensor_d435" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="sensor_d435" params="parent *origin">
<xacro:property name="M_PI" value="3.1415926535897931" />
<!-- The following values are approximate, and the camera node
publishing TF values with actual calibrated camera extrinsic values -->
<xacro:property name="d435_cam_depth_to_left_ir_offset" value="0.0"/>
<xacro:property name="d435_cam_depth_to_right_ir_offset" value="-0.050"/>
<xacro:property name="d435_cam_depth_to_color_offset" value="0.015"/>
<!-- The following values model the aluminum peripherial case for the
D435 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="d435_cam_width" value="0.090"/>
<xacro:property name="d435_cam_height" value="0.025"/>
<xacro:property name="d435_cam_depth" value="0.02505"/>
<xacro:property name="d435_cam_mount_from_center_offset" value="0.0149"/>
<!-- The following offset is relative the the physical D435 camera peripherial
camera tripod mount -->
<xacro:property name="d435_cam_depth_px" value="${d435_cam_mount_from_center_offset}"/>
<xacro:property name="d435_cam_depth_py" value="0.0175"/>
<xacro:property name="d435_cam_depth_pz" value="${d435_cam_height/2}"/>
<material name="aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>
<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="camera_bottom_screw_frame" />
</joint>
<link name="camera_bottom_screw_frame"/>
<joint name="camera_link_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_py} ${d435_cam_depth_pz}" rpy="0 0 0"/>
<parent link="camera_bottom_screw_frame"/>
<child link="camera_link" />
</joint>
<link name="camera_link">
<visual>
<origin xyz="${d435_cam_mount_from_center_offset} ${-d435_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
<mesh filename="package://realsense2_camera/meshes/d435.dae" />
<!--<mesh filename="package://realsense2_camera/meshes/d435/d435.dae" />-->
</geometry>
<material name="aluminum"/>
</visual>
<collision>
<origin xyz="0 ${-d435_cam_depth_py} 0" rpy="0 0 0"/>
<geometry>
<box size="${d435_cam_depth} ${d435_cam_width} ${d435_cam_height}"/>
</geometry>
</collision>
<inertial>
<!-- The following are not reliable values, and should not be used for modeling -->
<mass value="0.564" />
<origin xyz="0 0 0" />
<inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257" />
</inertial>
</link>
<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame" />
</joint>
<link name="camera_depth_frame"/>
<joint name="camera_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>
<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_left_ir_frame" />
</joint>
<link name="camera_left_ir_frame"/>
<joint name="camera_left_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_left_ir_frame" />
<child link="camera_left_ir_optical_frame" />
</joint>
<link name="camera_left_ir_optical_frame"/>
<!-- camera right IR joints and links -->
<joint name="camera_right_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_right_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_right_ir_frame" />
</joint>
<link name="camera_right_ir_frame"/>
<joint name="camera_right_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_right_ir_frame" />
<child link="camera_right_ir_optical_frame" />
</joint>
<link name="camera_right_ir_optical_frame"/>
<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_color_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_color_frame" />
</joint>
<link name="camera_color_frame"/>
<joint name="camera_color_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_color_frame" />
<child link="camera_color_optical_frame" />
</joint>
<link name="camera_color_optical_frame"/>
</xacro:macro>
</robot>
......@@ -3,6 +3,7 @@
<xacro:include filename="$(find sphero_rvr_description)/model/sphero_rvr.urdf.xacro"/>
<xacro:include filename="$(find lss_4dof_description)/model/lss_4dof.urdf.xacro"/>
<xacro:include filename="$(find minibot)/model/d435.urdf.xacro" />
<xacro:lss_4dof name="lss_4dof" parent="battery_holder_link">
<origin xyz="0.0 -0.0465 0.019" rpy="0 0 ${M_PI/2}"/>
......@@ -77,21 +78,24 @@
<xacro:insert_block name="negligible_inertia"/>
</inertial>
<visual>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<origin xyz="0.0545 -0.0523 0.0385" rpy="0 0 ${M_PI/2}"/>
<geometry>
<mesh filename="package://minibot/meshes/realsense_mount.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="White"/>
<material name="Arm/White"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.042" rpy="0 0 0"/>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.06 0.03 0.04"/>
<box size="0.05 0.03 0.03"/>
</geometry>
</collision>
</link>
<sensor_d435 parent="camera_mount_link">
<origin xyz="0.0 0.022 0.055" rpy="0 -${M_PI/2} -${M_PI/2}"/>
</sensor_d435>
</xacro:macro>
</robot>
## Nvidia Jetson Ubuntu Image
This directory contains scripts and configurations to rebuild the Nvidia Jetson Image [0] for our minibot. It is based on work of pythops [1].
- [x] Build a Base Jetson Nano Ubuntu 20.04 image. This is based on https://github.com/pythops/jetson-nano-image/
- [x] ROS Noetic from the Ubuntu Repos
- [x] Nvidia, Intel Drivers from Manufacturer and/or Ubuntu Repos
- [x] Clone this repo for the Hardware Drivers and ROS Packages (Sphero RVR, Lynxmotion Arm, Intel Realsense)
- [ ] Include Vision Part of LeoBot (https://git.uibk.ac.at/RoboCupTeamTyrolics/robocupatwork)
- [ ] Test Yolo Nano https://arxiv.org/abs/2107.08430 ("0.91M parameters and 1.08G FLOPs, we get 25.3% AP on COCO")
**Note:** This image is "minimal" and has no GUI interface. You need to connect via ssh - or at a later stage maybe via a webbrowser.
### Build Instruction
Exports:
```
export JETSON_NANO_BOARD=jetson-nano-2gb
export JETSON_BUILD_DIR=/mnt/EXT/jetson_nano
export JETSON_ROOTFS_DIR=/mnt/EXT/jetson-rootdir
```
#### Prepare the root file-system
```
sudo -E ./create-rootfs.sh
```
#### Use ansible to install apropriate files and configurations
```
cd ansible
sudo -E $(which ansible-playbook) jetson.yaml
cd ..
```
##### Create the sd card image and flash
```
sudo -E ./create-image.sh
# flash image with
sudo ./flash-image.sh /path/to/jetson.img /dev/mmcblk0
# or with balena and resize manually
balena-etcher-electron
# resize disk
sudo gprated
sudo e2fsck -f /dev/mmcblk0
sudo resize2fs -f /dev/mmblck0
```
#### More information on the Ubuntu Jetson Nano Base image
- [0] https://docs.nvidia.com/jetson/l4t/index.html#page/Tegra%20Linux%20Driver%20Package%20Development%20Guide/updating_jetson_and_host.html
- [1] https://github.com/pythops/jetson-nano-image/ (supported boards)
- [Jetson nano](https://developer.nvidia.com/embedded/jetson-nano-developer-kit)
- [Jetson nano 2GB](https://developer.nvidia.com/embedded/jetson-nano-2gb-developer-kit)
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment