Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Nvidia_TX1: add ros install scripts #18

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
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
77 changes: 77 additions & 0 deletions Nvidia_JTX1/Ubuntu/10_setup_ros.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
#!/bin/bash

# this script should be run as the apsync user
# these instructions come from Dan Pollock, posting can be found here: https://www.facebook.com/groups/pixhawk2/permalink/1192680427481244/

set -e
set -x

pushd .

# setup reference to ros packages
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116
sudo apt-get update

# install ros
sudo apt-get install -y ros-kinetic-ros-base python-rosinstall ros-kinetic-mavros ros-kinetic-rtabmap-ros ros-kinetic-robot-state-publisher
sudo c_rehash /etc/ssl/certs
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is that really needed? (maybe tx1 specific ?)

sudo rosdep init
rosdep update

# add environment to .bashrc
echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
source ~/.bashrc

# install the ZED SDK using 7_setup_zed.sh

# install zed-ros-wrapper
mkdir -p ~/catkin_zed/src
cd ~/catkin_zed/src
git clone https://github.com/stereolabs/zed-ros-wrapper.git

# create workspace
# Note: this seems to fail because some ROS variables are not being set
cd ~/catkin_zed/src
/opt/ros/kinetic/bin/catkin_init_workspace
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this isn't really need normally, the first call of catkin_make will init the workspace

cd ~/catkin_zed
/opt/ros/kinetic/bin/catkin_make
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

normally, catkin_make should be accessible directly since the setup.bash has been sourced


# kill src directory and build again
rm -rf ~/catkin_zed/src
mkdir -p ~/catkin_zed/src
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this look strange

Copy link
Contributor Author

@rmackay9 rmackay9 Feb 6, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, it's strange that we need to do the make twice but the first time around the make always fails. I have no idea why at this moment and neither does Dan Pollock..

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can understand that catkin_make failed due to missing dependencies, or non-generated msg before need, remove the src shouldn't make a difference !
I don't have the hardware to test ... so I will thrust you on that. I make only general comments ! ^^

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I turned that into Stereolabs. They said they would fix in the next release. Its something in either the build or devel directories that get built the first time through. If you save those off from a good build and add them to a new workspace before you try and build it the build will succeed first time through.

cd ~/catkin_zed/src
git clone https://github.com/stereolabs/zed-ros-wrapper.git
cd ~/catkin_zed
/opt/ros/kinetic/bin/catkin_make

popd

# cp zed_rtabmap_launch file to /opt/ros/kinetic/share/rtabmap_ros/launch
sudo cp ./zed_rtabmap.launch /opt/ros/kinetic/share/rtabmap_ros/launch
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

roscp rtabmap_ros rtabmap.launch ./zed_rtabmap.launch

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

haa understand! you are on the otherside ... well in fact you don't need to be in a workspace to call a .launch . Just roslaunch PATH_TO_FILE/zed_rtabmap.launch will work!

# old instructions for above:
# cd to /opt/ros/kinetic/share/rtabmap_ros/launch
# sudo cp /opt/ros/kinetic/share/rtabmap_ros/launch/rtabmap.launch /opt/ros/kinetic/share/rtabmap_ros/launch/zed_rtabmap.launch
# sudo vi /opt/ros/kinetic/share/rtabmap_ros/launch/zed_rtabmap.launch
# replace "/camera/rgb" with "/camera/zed/rgb"
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this step is missing ! something like maybe
sed -i -e "s/rgb/zed/rgb/g" ./zed_rtabmap.launch

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

so this is not needed


# put startup scripts in place
mkdir ~/start_ros
cp start_1_roscore.sh ~/start_ros
cp start_2_zed_wrapper.sh ~/start_ros
cp start_3_rosrun.sh ~/start_ros
cp start_4_rtabmap.sh ~/start_ros

# test rosrun zed_wrapper
# first terminal
# roscore
# second terminal:
# export ROS_NAMESPACE=camera
# source ~/catkin_zed/devel/setup.bash
# roslaunch zed_wrapper zed.launch
# third terminal window:
# export ROS_NAMESPACE=camera
# source ~/catkin_zed/devel/setup.bash
# rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link zed_initial_frame 100 &
# test viewer on client
# roslaunch rtabmap_ros zed_rtabmap.launch rtabmap_args:="--delete_db_on_start" depth_topic:=/camera/zed/depth/depth_registered
18 changes: 0 additions & 18 deletions Nvidia_JTX1/Ubuntu/7_setup_zed.sh

This file was deleted.

26 changes: 26 additions & 0 deletions Nvidia_JTX1/Ubuntu/9_setup_zed.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#!/bin/bash

# this script sets up the ZED camera
# this should be run as the "apsync" user

# store current directory
pushd .

# download install scripts from stereolabs
mkdir -p ~/Downloads
cd ~/Downloads
# wget --no-check-certificate https://www.stereolabs.com/download_327af3/ZED_SDK_Linux_JTX1_v1.2.0_64b_JetPack23.run
wget --no-check-certificate https://dl.dropboxusercontent.com/u/3852647/ZED/ZED_SDK_Linux_JTX1_v1.2.0_64b_JetPack23.run

# install (user will need to press "Q"
echo "Installing ZED camera SDK, you must manually accept the license agreement (press Y), enter root password and press enter to accept the default install directory"
chmod +x ./ZED_SDK_Linux_JTX1_v1.2.0_64b_JetPack23.run
./ZED_SDK_Linux_JTX1_v1.2.0_64b_JetPack23.run

# startup zed camera's Depth Viewer to force download of calibration file for this particular camera
# this may require permissioning apsync to use the screen, "sudo xhost +SI:localuser:apsync"
# Note: we should change this to a user runnable script to download the config for each user's camera
/usr/local/zed/tools/ZED \ Depth\ Viewer

# return to stored directory
popd
4 changes: 4 additions & 0 deletions Nvidia_JTX1/Ubuntu/start_1_roscore.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
#!/bin/bash

# start roscore
roscore
6 changes: 6 additions & 0 deletions Nvidia_JTX1/Ubuntu/start_2_zed_wrapper.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#!/bin/bash

# start rosrun
export ROS_NAMESPACE=camera
source ~/catkin_zed/devel/setup.bash
roslaunch zed_wrapper zed.launch
6 changes: 6 additions & 0 deletions Nvidia_JTX1/Ubuntu/start_3_rosrun.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#!/bin/bash

# start rosrun
export ROS_NAMESPACE=camera
source ~/catkin_zed/devel/setup.bash
rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link zed_initial_frame 100 &
9 changes: 9 additions & 0 deletions Nvidia_JTX1/Ubuntu/start_4_rtabmap.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#!/bin/bash

# override home in case this is being run from different user
export HOME=/home/apsync

# start rosrun
export ROS_NAMESPACE=camera
source ~/catkin_zed/devel/setup.bash
roslaunch rtabmap_ros zed_rtabmap.launch rtabmap_args:="--delete_db_on_start" depth_topic:=/camera/zed/depth/depth_registered
197 changes: 197 additions & 0 deletions Nvidia_JTX1/Ubuntu/zed_rtabmap.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,197 @@

<launch>
<!-- Convenience launch file to launch odometry, rtabmap and rtabmapviz nodes at once -->

<!-- For stereo:=false
Your RGB-D sensor should be already started with "depth_registration:=true".
Examples:
$ roslaunch freenect_launch freenect.launch depth_registration:=true
$ roslaunch openni2_launch openni2.launch depth_registration:=true -->

<!-- For stereo:=true
Your camera should be calibrated and publishing rectified left and right
images + corresponding camera_info msgs. You can use stereo_image_proc for image rectification.
Example:
$ roslaunch rtabmap_ros bumblebee.launch -->

<!-- Choose between RGB-D and stereo -->
<arg name="stereo" default="false"/>

<!-- Choose visualization -->
<arg name="rtabmapviz" default="true" />
<arg name="rviz" default="false" />

<!-- Localization-only mode -->
<arg name="localization" default="false"/>

<!-- Corresponding config files -->
<arg name="cfg" default="" /> <!-- To change RTAB-Map's parameters, set the path of config file (*.ini) generated by the standalone app -->
<arg name="gui_cfg" default="~/.ros/rtabmap_gui.ini" />
<arg name="rviz_cfg" default="-d $(find rtabmap_ros)/launch/config/rgbd.rviz" />

<arg name="frame_id" default="camera_link"/> <!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
<arg name="namespace" default="rtabmap"/>
<arg name="database_path" default="~/.ros/rtabmap.db"/>
<arg name="queue_size" default="10"/>
<arg name="wait_for_transform" default="0.2"/>
<arg name="rtabmap_args" default=""/> <!-- delete_db_on_start, udebug -->
<arg name="launch_prefix" default=""/> <!-- for debugging purpose, it fills launch-prefix tag of the nodes -->
<arg name="approx_sync" default="true"/> <!-- if timestamps of the input topics are not synchronized -->

<!-- RGB-D related topics -->
<arg name="rgb_topic" default="/camera/zed/rgb/image_rect_color" />
<arg name="depth_topic" default="/camera/zed/depth_registered/image_raw" />
<arg name="camera_info_topic" default="/camera/zed/rgb/camera_info" />

<!-- stereo related topics -->
<arg name="stereo_namespace" default="/stereo_camera"/>
<arg name="left_image_topic" default="$(arg stereo_namespace)/left/image_rect_color" />
<arg name="right_image_topic" default="$(arg stereo_namespace)/right/image_rect" /> <!-- using grayscale image for efficiency -->
<arg name="left_camera_info_topic" default="$(arg stereo_namespace)/left/camera_info" />
<arg name="right_camera_info_topic" default="$(arg stereo_namespace)/right/camera_info" />

<arg name="compressed" default="false"/> <!-- If you want to subscribe to compressed image topics -->
<!-- For depth_topic, "compressedDepth" image_transport is used. -->
<!-- For rgb_topic, see "rgb_image_transport" argument. -->
<arg name="rgb_image_transport" default="compressed"/> <!-- Common types: compressed, theora (see "rosrun image_transport list_transports") -->

<arg name="subscribe_scan" default="false"/>
<arg name="scan_topic" default="/scan"/>

<arg name="subscribe_scan_cloud" default="false"/>
<arg name="scan_cloud_topic" default="/scan_cloud"/>

<arg name="visual_odometry" default="true"/> <!-- Launch rtabmap visual odometry node -->
<arg name="odom_topic" default="/odom"/> <!-- Odometry topic used if visual_odometry is false -->
<arg name="odom_args" default="$(arg rtabmap_args)"/>

<!-- These arguments should not be modified directly, see referred topics without "_relay" suffix above -->
<arg if="$(arg compressed)" name="rgb_topic_relay" default="$(arg rgb_topic)_relay"/>
<arg unless="$(arg compressed)" name="rgb_topic_relay" default="$(arg rgb_topic)"/>
<arg if="$(arg compressed)" name="depth_topic_relay" default="$(arg depth_topic)_relay"/>
<arg unless="$(arg compressed)" name="depth_topic_relay" default="$(arg depth_topic)"/>
<arg if="$(arg compressed)" name="left_image_topic_relay" default="$(arg left_image_topic)_relay"/>
<arg unless="$(arg compressed)" name="left_image_topic_relay" default="$(arg left_image_topic)"/>
<arg if="$(arg compressed)" name="right_image_topic_relay" default="$(arg right_image_topic)_relay"/>
<arg unless="$(arg compressed)" name="right_image_topic_relay" default="$(arg right_image_topic)"/>

<!-- Nodes -->
<group ns="$(arg namespace)">

<!-- RGB-D Odometry -->
<group unless="$(arg stereo)">
<node if="$(arg compressed)" name="republish_rgb" type="republish" pkg="image_transport" args="$(arg rgb_image_transport) in:=$(arg rgb_topic) raw out:=$(arg rgb_topic_relay)" />
<node if="$(arg compressed)" name="republish_depth" type="republish" pkg="image_transport" args="compressedDepth in:=$(arg depth_topic) raw out:=$(arg depth_topic_relay)" />

<node if="$(arg visual_odometry)" pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen" args="$(arg odom_args)" launch-prefix="$(arg launch_prefix)">
<remap from="rgb/image" to="$(arg rgb_topic_relay)"/>
<remap from="depth/image" to="$(arg depth_topic_relay)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>

<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="approx_sync" type="bool" value="$(arg approx_sync)"/>
<param name="config_path" type="string" value="$(arg cfg)"/>
<param name="queue_size" type="int" value="$(arg queue_size)"/>
</node>
</group>

<!-- Stereo Odometry -->
<group if="$(arg stereo)">
<node if="$(arg compressed)" name="republish_left" type="republish" pkg="image_transport" args="compressed in:=$(arg left_image_topic) raw out:=$(arg left_image_topic_relay)" />
<node if="$(arg compressed)" name="republish_right" type="republish" pkg="image_transport" args="compressed in:=$(arg right_image_topic) raw out:=$(arg right_image_topic_relay)" />

<node if="$(arg visual_odometry)" pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen" args="$(arg odom_args)" launch-prefix="$(arg launch_prefix)">
<remap from="left/image_rect" to="$(arg left_image_topic_relay)"/>
<remap from="right/image_rect" to="$(arg right_image_topic_relay)"/>
<remap from="left/camera_info" to="$(arg left_camera_info_topic)"/>
<remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>

<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="approx_sync" type="bool" value="$(arg approx_sync)"/>
<param name="config_path" type="string" value="$(arg cfg)"/>
<param name="queue_size" type="int" value="$(arg queue_size)"/>
</node>
</group>

<!-- Visual SLAM (robot side) -->
<!-- args: "delete_db_on_start" and "udebug" -->
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="$(arg rtabmap_args)" launch-prefix="$(arg launch_prefix)">
<param if="$(arg stereo)" name="subscribe_depth" type="bool" value="false"/>
<param unless="$(arg stereo)" name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_stereo" type="bool" value="$(arg stereo)"/>
<param name="subscribe_scan" type="bool" value="$(arg subscribe_scan)"/>
<param name="subscribe_scan_cloud" type="bool" value="$(arg subscribe_scan_cloud)"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="database_path" type="string" value="$(arg database_path)"/>
<param name="approx_sync" type="bool" value="$(arg approx_sync)"/>
<param name="config_path" type="string" value="$(arg cfg)"/>
<param name="queue_size" type="int" value="$(arg queue_size)"/>

<remap from="rgb/image" to="$(arg rgb_topic_relay)"/>
<remap from="depth/image" to="$(arg depth_topic_relay)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>

<remap from="left/image_rect" to="$(arg left_image_topic_relay)"/>
<remap from="right/image_rect" to="$(arg right_image_topic_relay)"/>
<remap from="left/camera_info" to="$(arg left_camera_info_topic)"/>
<remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>

<remap from="scan" to="$(arg scan_topic)"/>
<remap from="scan_cloud" to="$(arg scan_cloud_topic)"/>
<remap unless="$(arg visual_odometry)" from="odom" to="$(arg odom_topic)"/>

<!-- localization mode -->
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
</node>

<!-- Visualisation RTAB-Map -->
<node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(arg gui_cfg)" output="screen" launch-prefix="$(arg launch_prefix)">
<param if="$(arg stereo)" name="subscribe_depth" type="bool" value="false"/>
<param unless="$(arg stereo)" name="subscribe_depth" type="bool" value="true"/>
<param name="subscribe_stereo" type="bool" value="$(arg stereo)"/>
<param name="subscribe_scan" type="bool" value="$(arg subscribe_scan)"/>
<param name="subscribe_scan_cloud" type="bool" value="$(arg subscribe_scan_cloud)"/>
<param name="subscribe_odom_info" type="bool" value="$(arg visual_odometry)"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="wait_for_transform_duration" type="double" value="$(arg wait_for_transform)"/>
<param name="queue_size" type="int" value="$(arg queue_size)"/>

<remap from="rgb/image" to="$(arg rgb_topic_relay)"/>
<remap from="depth/image" to="$(arg depth_topic_relay)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>

<remap from="left/image_rect" to="$(arg left_image_topic_relay)"/>
<remap from="right/image_rect" to="$(arg right_image_topic_relay)"/>
<remap from="left/camera_info" to="$(arg left_camera_info_topic)"/>
<remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>

<remap from="scan" to="$(arg scan_topic)"/>
<remap from="scan_cloud" to="$(arg scan_cloud_topic)"/>
<remap unless="$(arg visual_odometry)" from="odom" to="$(arg odom_topic)"/>
</node>

</group>

<!-- Visualization RVIZ -->
<node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="$(arg rviz_cfg)"/>
<node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb">
<remap from="left/image" to="$(arg left_image_topic_relay)"/>
<remap from="right/image" to="$(arg right_image_topic_relay)"/>
<remap from="left/camera_info" to="$(arg left_camera_info_topic)"/>
<remap from="right/camera_info" to="$(arg right_camera_info_topic)"/>
<remap from="rgb/image" to="$(arg rgb_topic_relay)"/>
<remap from="depth/image" to="$(arg depth_topic_relay)"/>
<remap from="rgb/camera_info" to="$(arg camera_info_topic)"/>
<remap from="cloud" to="voxel_cloud" />

<param name="decimation" type="double" value="2"/>
<param name="voxel_size" type="double" value="0.02"/>
<param name="approx_sync" type="bool" value="$(arg approx_sync)"/>
</node>

</launch>