DreamVu
www.dreamvu.com
PAL ROS Application Note
The DreamVu PAL cameras capture stereoscopic 360° panoramic images of the scene. These images can be used for comprehensive situational awareness and dense 360° 3D reconstruction of the scene. This document provides guidance for using the PAL camera with ROS and ROS2. The document is divided into the following sections:
To install the PAL on your platform, follow the information in the PAL Design Guide to determine where and how to mount the device and what parameters to compute to establish the correct frame of reference for the PAL Data.
To install the driver and SDK in your own environment, follow the instructions here. Refer to the setup guide for instructions on using the Explorer application to determine correct imaging algorithm parameters for your environment. The Explorer application will save out a configuration file for use in the runtime environment.
Once mounted, the device frame of reference can be added to the ROS environment by publishing a static transform. Run the following command in a new terminal window and add values for the translation (x,y,z) offset and rotation (yaw) offset as shown in the design guide. Note the following:
# FOR ROS $ cd ~/catkin_ws/ $ source ./devel/setup.bash $ rosrun tf static_transform_publisher <x-offset> <y-offset> <z-offset> <yaw-offset> <pitch=0.0> <roll=0.0> base_link pal 10 |
# FOR ROS2 $ cd ~/catkin_ws/ $ . install/setup.bash $ ros2 run tf2_ros static_transform_publisher <x-offset> <y-offset> <z-offset> <yaw-offset> <pitch=0.0> <roll=0.0> base_link pal |
Once the configuration files are complete and installed, you may verify whether the system is working correctly.
One or more objects should be placed around the device to test the installation. Once the scene is set up, launch the ROS master for ROS from a new terminal window. For ROS2 there is no ROS master.
# FOR ROS $ cd ~/catkin_ws/ $ source devel/setup.bash $ roscore |
# FOR ROS2 $ cd ~/catkin_ws/ $ . install/setup.bash |
In a second terminal window, run these commands:
# FOR ROS $ cd ~/DreamVu/PAL $ cp -r dreamvu_pal_navigation/ ~/catkin_ws/src $ cd ~/catkin_ws/ $ source devel/setup.bash $ rosparam load src/dreamvu_pal_navigation/laser_filter.yml |
#For ROS2 $ cd ~/DreamVu/PAL $ cp -r dreamvu_pal_navigation/ ~/catkin_ws/src $ cd ~/catkin_ws/ $ . install/setup.bash $ ros2 param load publisher src/dreamvu_pal_navigation/laser_filter.yml |
In a third window, run these commands (for both ROS and ROS2)
$ cd ~/DreamVu/PAL $ ./ros_demo.sh |
It will ask for an integer input(1-7). Please enter 1 and press Enter.
This will display the panorama in an Rviz or Rviz2 window with the left panorama along with the depth map and the 3D point cloud as illustrated in the figure below.
The ros_demo.sh script shows the RGB image with the depth map and the point cloud.
To measure the range to verify the accuracy provided by the PAL Camera, the user can select the RangeScan topic that is published and measure the distance to one of the objects in the scene as shown in the figures below:
Using the measure tool in the Rviz taskbar, the distance from the center of the grid to the obstacle can be determined as shown in the image below, using the measure tool highlighted in red. Note that in Rviz, the overlaid range scan image, the depth image and the range scan topics are active in the image below:
Compare the measured and computed distances and verify the system is working as expected (refer to the device data sheet for expected accuracy under different conditions). If the accuracy is not as expected, verify the various parameters were correctly entered into the configuration files, including the correct height of the device above the floor. If there are no configuration errors, contact DreamVu technical support for assistance.
The PAL Camera can also be mounted with a non-zero pitch as explained in detail in the PAL Design Guide. In such a case, the ros_demo.sh script shows the following output when launched. It may be noted that the panorama will be corrected to display a horizontal-facing view. One may also note the contouring of the image due to the inclination of the upward and downward blind spots in the device field of view when rotated in pitch.
The output of the ros_demo.sh script when the camera is mounted at a pitch of 25°
The PAL Starter Kit includes a wrapper package dreamvu_pal_navigation folder which facilitates the integration of PAL with ROS. The stereoscopic panoramas, the Range Scan (depth-scan), the depth map, and the 3D point cloud generated by the PAL camera can be accessed in ROS.
The dreamvu_pal_navigation package consists of a node of publisher type with the name pal_publisher_node. This node publishes ROS topics corresponding to different informations streams from PAL that are listed in the following table:
Data published | Topic | ROS Message Type | ROS2 Message Type |
Left panorama | /dreamvu/pal/odoa/get/stereo/left | sensor_msgs::Image | sensor_msgs::msgs::Image |
Right panorama | /dreamvu/pal/odoa/get/stereo/right | sensor_msgs::Image | sensor_msgs::msgs::Image |
Overlaid Image | /dreamvu/pal/odoa/get/left | sensor_msgs::Image | sensor_msgs::msgs::Image |
Range-Scan | /dreamvu/pal/odoa/get/scan | sensor_msgs::LaserScan | sensor_msgs::msgs::LaserScan |
Depth Map | /dreamvu/pal/odoa/get/depth | sensor_msgs::Image | sensor_msgs::msgs::Image |
Point Cloud | /dreamvu/pal/odoa/get/point_cloud | sensor_msgs::PointCloud2 | sensor_msgs::msg::PointCloud2 |
List of rostopics published by the publisher node
The Point Cloud from the PAL camera is published using the sensor_msgs::PointCloud2/sensor_msgs::msg::PointCloud2 in a reference frame that is denoted as the pal frame. The point cloud consists of up to 150K points published for each frame from the camera. The point cloud can be integrated into the end-user application by subscribing to the above mentioned topic.
The Range Scan from the PAL camera is published using the sensor_msgs::LaserScan/sensor_msgs::msg::LaserScan in a reference frame denoted as the pal frame. Note: The Range Scan consists of 672 points at an angular resolution of 0.53° per point for the 360° horizontal field of view.
The dreamvu_pal_navigation package consists of a set of properties contained within a text file namedSavedPalProperties.txt which is present at the following location ~/DreamVu/PAL/Explorer/SavedPalProperties.txt. This file contains the properties that configure the Range Scan output generated from the PAL camera and were initially defined by the Explorer application during setup. Based on the end application - mapping, obstacle detection, or navigation - these properties can be modified during deployment.
This section provides guidance for using the PAL camera for 2D Mapping and Navigation using standard packages available in ROS. The instructions provided in this section are applicable to ROS distros and not applicable to ROS2 distros.
This section describes the steps involved in mapping an area using the ROS Gmapping package. The first step is to run the publisher node by running the following commands:
On ROS, start the ros-master by starting roscore in a new terminal
$ roscore |
In another terminal window, the bash setup file for the catkin workspace can be sourced using the following command and a meta-data file containing parameters for filtering Range Scan can be loaded.
#For ROS $ cd catkin_ws/ $ source devel/setup.bash $ rosparam load src/dreamvu_pal_navigation/laser_filter.yml |
#For ROS2 $ cd ~/catkin_ws/ $ . install/setup.bash $ ros2 param load publisher src/dreamvu_pal_navigation/laser_filter.yml |
Next, the following command needs to be executed to start the publisher node
#For ROS $ rosrun dreamvu_pal_navigation publisher |
#For ROS2 $ ros2 run dreamvu_pal_navigation publisher |
The node will now advertise the list of topics mentioned above to the master. Once any subscriber is registered to a topic, the node will start publishing messages corresponding to that topic.
A list of recommended parameters for GMapping with PAL are provided here:
Parameter Name | Value |
angularUpdate | 0.1 |
linearUpdate | 0.1 |
particles | 1 |
xmin | -10.0 |
xmax | 10.0 |
ymin | -10.0 |
ymax | 10.0 |
maxUrange | 3.5 |
occ_thresh | 0.15 |
Recommended GMapping Parameters
These parameters can be by editing the launch file using this command:
$ gedit ~/catkin_ws/src/dreamvu_pal_navigation/launch/gmapping.launch |
Additional Notes :
Mounting Type | Mounting Height | Mapping / ODOA Range |
Low Mounting | Less than 20cm | 1.5m - 2m |
Moderate Mounting | 20cm - 60cm | 2m - 4m |
High Mounting | 60cm - 300cm | 4m - 10m |
The minimumScore parameter can be set to a high value (>10000) if the size of the room is large and if the robot is unable to localize well enough This increases the weighted dependence on mechanical odometry from the robot. The GMapping ROS package can now be launched using the provided gmapping.launch file in the dreamvu_pal_navigation package of the SDK.
Load the meta-data for Range Scan filtering in a new terminal, if not already loaded in to the master
# FOR ROS $ cd ~/catkin_ws/ $ source devel/setup.bash $ rosparam load src/dreamvu_pal_navigation/laser_filter.yml |
#For ROS2 $ cd ~/catkin_ws/ $ . install/setup.bash $ ros2 param load publisher src/dreamvu_pal_navigation/laser_filter.yml |
Now the user can launch the Gmapping package
#For ROS $ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation gmapping.launch |
#For ROS2 $ cd ~/catkin_ws $ . install/setup.bash $ ros2 launch dreamvu_pal_navigation gmapping.launch |
This launch file will open an Rviz window displaying the live map generated from the Range Scan of the PAL camera. Move the robot around the environment to generate a complete map. Since the Range Scan captures full 360° information, the robot may only need to traverse the environment once.
Figure 2.4 Rviz window showcasing GMapping with the PAL Range Scan
Once the mapping is complete, the map can be saved using the following command in a new terminal window.
#For ROS $ cd catkin_ws/ $ deactivate $ source devel/setup.bash $ rosrun map_server map_saver -f <filename> |
#For ROS2 $ cd ~/catkin_ws $ deactivate $ . install/setup.bash $ ros2 run map_server map_saver -f <filename> |
This command saves the map in two files named <filename>.pgm and <filename>.yaml. This map can be used further for obstacle detection and navigation.
The 2D Range Scan from the PAL camera uses the full 3D information in the field of view projected onto the 2D plane of the floor. It can be used to identify the distance to the nearest obstacle in all directions around the camera, including obstacles above the floor such as tabletops.
The Range Scan can be used for navigation in a mapped environment around the robot. Given a start and a goal position, the navigation framework identifies a path around the various static and dynamic obstacles in the scene, and provides command velocities to the wheels of the robot to reach the goal position. The static (or global) obstacles are identified using the map of the scene and for the dynamic (or local) obstacles we use PAL’s range scan. For path-planning and generating the command velocities for the robot, we use the move_base package in ROS. Once the command velocities are generated, the base_controller of the robot drives the robot to goal position.
The overall architecture of the Navigation stack in ROS is shown in this diagram:
Parameters for AMCL
Parameter Name | Value |
odom_model_type | diff-corrected |
odom_alpha1 | 0.002 |
odom_alpha2 | 0.002 |
odom_alpha3 | 0.002 |
odom_alpha4 | 0.002 |
laser_z_hit | 0.1 |
laser_z_rand | 0.9 |
transform_tolerance | 5.0 |
Parameters for the Local Costmap
Parameter Name | Value |
obstacle_range | 2.0 |
raytrace_range | 3.0 |
robot_radius | 0.3 |
inflation_radius | 0.3 |
cost_scaling_factor | 1 |
transform_tolerance | 10.0 |
global_frame | odom |
robot_base_frame | base_link |
update_frequency | 1.0 |
publish_frequency | 1.0 |
static_map | false |
rolling_window | true |
width | 10.0 |
height | 10.0 |
resolution | 0.05 |
Parameters for the Global Costmap
Parameter Name | Value |
obstacle_range | 2.0 |
raytrace_range | 3.0 |
robot_radius | 0.3 |
inflation_radius | 0.3 |
cost_scaling_factor | 1 |
transform_tolerance | 10.0 |
global_frame | map |
robot_base_frame | base_link |
update_frequency | 1.0 |
static_map | true |
Parameters for the Base Local Planner
Parameter Name | Value |
controller_frequency | 5.0 |
max_vel_x | 0.10 |
min_vel_x | 0.01 |
max_vel_theta | 0.3 |
min_in_place_vel_theta | 0.3 |
acc_lim_theta | 3.2 |
acc_lim_x | 2.5 |
acc_lim_y | 2.5 |
The dreamvu_pal_navigation package in ROS includes a launch file to run AMCL based navigation. The amcl.launch includes the path to the map file. This path needs to be updated to the path where the map is saved as shown in the example below:
<arg name="map_file" default="/home/dreamvu/catkin_ws/map.yaml"/> |
Once the path to the map is provide, the AMCL package can be launched as follows :
Load the meta-data for Range Scan filtering in a new terminal:
#For ROS $ cd catkin_ws/ $ source devel/setup.bash $ rosparam load src/dreamvu_pal_navigation/laser_filter.yml |
#For ROS2 $ cd catkin_ws/ $ . install/setup.bash $ ros2 param load src/dreamvu_pal_navigation/laser_filter.yml |
Now you can launch the AMCL package
#For ROS $ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation amcl.launch |
#For ROS2 $ cd ~/catkin_ws $ . install/setup.bash $ ros2 launch dreamvu_pal_navigation amcl.launch |
This will open an Rviz window similar to the one shown below :
Figure 2.5 Rviz window showcasing AMCL with the PAL Range Scan before aligning the Range Scan
The Range Scan and the map will be seen in the Rviz window. At startup, the alignment between the scan and the map will not be established. The initial pose estimate must be provided, before navigation, to align the scan to the map. In order to provide the initial pose and location estimate of the robot, the following steps need to be executed:
Figure 2.6 Selecting the Initial Pose Estimate of the Robot
The move_base package in ROS is used for path planning and computing the command velocities for each wheel of the robot. This package also provides the capability to configure the local and global costmaps and the local and global planners. Once the initial pose is established and the robot is set to navigate, the move_base package can be launched by running the following commands in a new terminal.
#For ROS $ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation move_base.launch |
#For ROS2 $ cd ~/catkin_ws $ . install/setup.bash $ ros2 launch dreamvu_pal_navigation move_base.launch |
Once launched, the user can subscribe to the local costmap, global costmap, local plan, global plan, robot’s foot print etc. Illustrations of the global and local costmaps are shown in Figures 2.7 and 2.8.
Figure 2.7 Local Cost Map surrounding the Robot
Figure 2.8 Global Cost Map across the full map of the environment
The costmaps provide an idea of the portions of the map where the robot can successfully navigate. In order to autonomously navigate the robot, a goal position needs to be specified to a physically approachable location in the map. In order to do so, the user can click on the 2D Nav Goal tool in the Rviz taskbar and provide the goal position and heading as shown in the figure below :
Figure 5.9 Setting the Goal Position and Target Heading for Navigation
Once the goal position is provided, the user may subscribe to the global plan and footprint of the robot to anticipate the trajectory to be followed by the robot as shown in Figure 2.10.
Once the goal position is provided, the robot will autonomously navigate and follow the anticipated trajectory to the target position, while avoiding any static or dynamic obstacles in its path that may be detected by the PAL Range Scan.
As per the mounting instructions provided in Step 2, we mount the PAL camera on the TurtleBot 2 using a custom mounting plate. To ensure the correct transform between the base_link frame of the robot and the pal frame of the camera, the following command can be executed in a new terminal window.
$ rostopic echo /tf |
This command will display the following information, which should be the same as the transformation between the PAL camera and the base_link of the robot.
:
The TurtleBot 2 can now be powered on and the bring-up activity can be performed by executing the following commands in a terminal window:
$ cd catkin_ws $ deactivate $ source devel/setup.bash $ roslaunch turtlebot_bringup minimal.launch |
A sound from the TurtleBot 2 will confirm that the bring-up was successful.
Note: It must be ensured that the TurtleBot is publishing to the /odom topic and that the tf-tree is updated with the tf between the odom and the base_link of the TurtleBot.
To check the list of topics being published, the following command can be used which splashes the topic list on the terminal window as shown below:
$ rostopic list |
The following command can be used to check the tf-tree:
$ cd catkin_ws/ $ deactivate $ source devel/setup.bash $ rosrun tf view_frames && evince frames.pdf |
Note: This command generates a transform-tree and saves it in a file called frames.pdf. The tf-tree must be equivalent to the tf-tree shown here.
To navigate the turtlebot, the following commands can be used in a terminal window to launch the teleoperation program.
$ cd catkin_ws $ deactivate $ source devel/setup.bash $ roslaunch turtlebot_teleop keyboard_teleop.launch |
The image shown below is the default view of the teleoperation window for the TurtleBot 2. For the purposes of this tutorial, we recommend and set the translation speed to 0.2m/s and the rotational speed to 0.3 rad/s.
We use this prescribed Navigation stack along with the Range Scan generated from the PAL camera for navigating an off-the-shelf TurtleBot 2 in a mapped scene. We assume that the map is created as described in Step 2.4 and the camera is mounted on the TurtleBot and the TurtleBot bringup is completed (Step 2.4.1).
The software includes a code sample that demonstrates different applications and use-cases that are enabled by rich 360° 3D information from the PAL camera. The code samples provide a framework to access the panoramic images and the Range Scan. To run the code samples, the user must navigate to the code_samples directory in the root folder of the SDK. To compile all the code samples present in the folder, the following command can be executed in a terminal window.
$ ./compile.sh |
The code sample corresponding to the Range Scan can be viewed by opening the 003_range_scan.cpp file. This code sample consists of simple functions and inline comments to get started. The user may run the corresponding executable as follows:
./003_range_scan_panorama.out |
Note : For the two-camera use case, users can also pass camera index 5 or 6 as an argument to switch previewing between two cameras if required. For example:
./003_range_scan_panorama.out 6 |
When the executable starts, the user will be able to see the range scan overlaid on the RGB panorama, with tuned ODOA and sensor properties. On pressing the Esc key, the executable can be terminated.
The software also supports multi-camera functionality, i.e. one can connect two PAL Cameras and a composite Range Scan is published as a ROS topic. Two-camera support is only provided for ROS distros and not yet available for ROS2 distros. This can be used in cases where two PAL cameras are mounted at different locations on the robot as illustrated in the figure below.
The user can specify the horizontal field of view for each PAL camera and the PAL software provides the functionality to create the final composite Range Scan. In order to use this functionality, the following steps can be followed :
The mounting of the two PAL cameras needs to be achieved in the same manner as described in the setup guide. Since both cameras are used simultaneously, the user needs to specify two sets of transformations (offsets) between the base link of the robot and the PAL cameras as specified in Step 2.3. The user may refer to Fig 2.1 for mounting instructions and follow the same procedure for both cameras. Once the transformations are identified, they can be published using the following commands
For the first camera :
$ rosrun tf static_transform_publisher <x-offset> <y-offset> <z-offset> <yaw-offset> <pitch=0.0> <roll=0.0> base_link pal 10 |
For the second camera :
$ rosrun tf static_transform_publisher <x-offset> <y-offset> <z-offset> <yaw-offset> <pitch=0.0> <roll=0.0> base_link pal_1 10 |
In order to visualize two laser scans as well as the composite laser scan in rviz :
Start the ROS master by typing the following command in a new terminal:
$ roscore |
Load the parameters for filtering laser scan on ROS parameter server in a new terminal.
$ cd catkin_ws/ $ source devel/setup.bash $ rosparam load src/dreamvu_pal_navigation/laser_filter.yml |
Run the following command in order to visualize two range scans. You can take assistance with this visualization to verify the transforms between two cameras.
$ roslaunch dreamvu_pal_navigation multi_scan_rviz.launch |
Once the transforms are correct, now you can merge the two laser scan using the following command :
$ roslaunch dreamvu_pal_navigation merge.launch |
After running the above commands, the pal publisher node will publish RGB images and the composite Range Scan from the two cameras. This can be visualized in Rviz as shown in the image below, where the overlaid Range Scan on each panorama is drawn in green and composite 2D Range Scan is shown in white.
Figure 2.11 Rviz window output for the composite Range Scan.
The steps to perform mapping are identical to the single camera approach with only one command change. Instead of using gmapping.launch the user must use gmapping_multicam.launch
$ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation gmapping_multicam.launch |
The steps to perform localization are identical to the single camera approach with only one command change. Instead of using amcl.launch the user must use amcl_multicam.launch
$ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation amcl_multicam.launch |
ROS is designed with distributed computing in mind. To deploy a ROS system across multiple machines, the following prerequisites need to be satisfied:
If the systems are on the same local system, the above prerequisites would be satisfied.
After the above conditions have been satisfied, in ROS2 nodes/topics would be automatically visible across systems. For ROS1 follow the below steps:
For instance, let's consider a scenario where the IP address of the master system is 192.168.1.1, and that of the host system is 192.168.1.2. The master system needs to publish Range-Scan (mentioned here) and the host system needs to subscribe to it. In order to establish communication between these systems effectively, the user should adhere to the following sequence of actions:
$ cd ~/catkin_ws $ source devel/setup.bash $ roscore |
$ export ROS_MASTER_URI=http://192.168.1.1:11311 $ export ROS_IP="192.168.1.1" |
$ cd ~/catkin_ws $ source devel/setup.bash $ roslaunch dreamvu_pal_navigation scan_rviz.launch |
$ cd ~/catkin_ws $ source devel/setup.bash $ export ROS_MASTER_URI=http://192.168.1.1:11311 $ rostopic hz /dreamvu/pal/odoa/get/scan |
For more information refer to “Use ROS 2 with Fast-DDS Discovery Server” for ROS2 and "ros/MultipleMachines" for ROS.
To establish a direct Ethernet connection between multiple systems, please adhere to the outlined procedure below. Replicate these steps on each system you intend to interconnect.
$ printf 'set connection.id DirectConnect\nset ipv4.method manual\nset ipv4.addresses 192.168.1.1/24\nsave\nyes\nquit\n' | nmcli connection edit type ethernet |
net.core.wmem_max = 16777216 net.core.wmem_default = 131072 net.core.rmem_max = 16777216 net.core.rmem_default = 131072 net.ipv4.tcp_rmem = 4096 131072 16777216 net.ipv4.tcp_wmem = 4096 131072 16777216 net.ipv4.tcp_mem = 4096 131072 16777216 net.core.netdev_max_backlog = 30000 net.ipv4.ipfrag_high_threshold = 8388608 run /sbin/sysctl -p |
$ sudo su $ cat optimise_network_perf.txt >> /etc/sysctl.conf $ exit |
By following these steps, you can successfully establish a direct Ethernet connection among your chosen systems. Should you encounter any difficulties during the setup process, please do not hesitate to seek further assistance.
The package comes with a udp broadcaster present in the dreamvu_pal_navigation ros package of the Firmware package. Please follow the instructions to start the broadcasting of scan data packets.
$ cp dreamvu_pal_navigation ~/catkin_ws/src |
For example:
broadcastIP = "192.168.0.118"; broadcastPort = 5000; |
$ source devel/setup.bash $ catkin_make $ roslaunch dreamvu_pal_navigation broadcast.launch |
Packets will be sent to the set IP and port no where each packet will have the 32 bytes of header and rest of the data as laser scan.
If the below error is observed during ROS installation please follow steps mentioned below to resolve it.
Issue:
CMake Error at /opt/ros/melodic/share/cv_bridge/cmake/cv_bridgeConfig.cmake:113 (message): Project 'cv_bridge' specifies '/usr/include/opencv' as an include dir, which is not found. It does neither exist as an absolute directory nor in '${{prefix}}//usr/include/opencv'. |
Fix:
Please follow these steps to resolve the issue:
The PAL is designed to measure distances within a full 360◦ field of view. A single scan corresponding to one frame of the camera capture yields a sequence of scan points (also called samples). The number of scan points within a scan is defined by the parameter num_points_scan.
Each scan point consists of a distance value for a corresponding angle. However, since measurements are performed with a uniform angular resolution (depending on the parameter num_points_scan), the actual scan data output typically just gives distance for each sample. The corresponding angular reading can be reconstructed by adding up the angular increments from the starting angle of the scan i.e min_scan_angle.
The yaw offset is relative to the forward facing direction on the robot and must be computed based on the mounting orientation of the PAL. As a 360° device, the PAL has no intrinsic yaw reference and each implementation requires calibration to determine the correct offset. Depending on the mounting location and field of view, the 0° direction may or may not be in the field of view. The yaw offset can be computed by identifying the front or the heading of the robot relative to the horizontal field-of-view of the PAL camera. As an example, the PAL panorama (at the highest resolution) consists of 672 columns and if the heading or front of the robot corresponds to column 200. Then the yaw offset (in radians) can be computed as:
offsetyaw
When the translation and rotation offsets from the robot’s baselink are registered in ROS, the positive x axis for the PAL is directed outward at the center column of the horizontal field of view as set in the PAL configuration file.
The plane formed by the ground is called a scan plane. All measurements from the PAL are recorded in this plane. The scan data is represented within a polar coordinate system. The pole of the coordinate system is located at the optical center of the device found at the axis through the vertical center line (the Z axis of the sensor coordinate system) and at the height of the ‘horizon’ line of the mirror assembly. This defines the axis of rotation (Z-axis). The reference for yaw angle measurements (polar axis) is at 0° azimuth and equivalent to the X-axis of the sensor coordinate system.
By default, the PAL uses a right-hand coordinate system. The scan angle increases counter-clockwise (ccw) about the positive z axis. The following figure shows an example for a laser scan with min_scan_angle of zero and max_scan_angle of 120°. If the max_num_points_scan is 16, it will have an angular increment of 7.5°.
To register the polar coordinate system of the PAL to the Cartesian system of the robot, use the following conventions:
Once the translational and yaw-offsets are computed, register the polar system of PAL to the Cartesian system of the robot in ROS or your other software infrastructure.
Distance readings are typically output as unsigned 32-bit integer values in mm. In case of invalid measurements the distance reading is set to 0xFFFFFFFF.
The UDP/IP-based scan data output provides a low latency channel for scan data transmission. Each scan data packet is sent as a separate UDP message (datagram). The client application can make use of all received scan data packets, since every scan data packet incorporates a full scan data header which allows it to process the contained scan data separately.
Scan data packet | ||
Type | Name | Description |
Packet Header | ||
uint16 | magic | magic byte (0xa25c) marking the beginning of a packet |
uint16 | num_points_scan | number of scan points within scan depending on configured FOV |
float32 | protocol_version | Version of the software provided by DreamVu |
float32 | min_scan_angle | absolute angle for the starting FOV in the ccw direction. |
float32 | max_scan_angle | absolute angle for the ending FOV in the ccw direction |
uint64 | Timestamp sec | Epoch timestamp |
uint64 | Timestamp nsec | |
Scan Point Data | ||
uint32[num_points_scan] | distance | measured distance (in mm) Invalid measurements return 0xFFFFFFFF |
For additional information and to get started on more in-depth evaluation using your own platform, see the following guides:
PAL Datasheet - Provides detailed specifications for the PAL Device.
Starter Kit Setup Guide - The quickest way to start your evaluation of any of the PAL family of cameras.
Code Samples - Provides detailed guidance on using various sample programs.
GPIO & UART Application Note - Provides technical documentation for the SDK and integration as the GPIO & UART interface.
API Documentation - Provides API documentation.
PAL Design Integration Guide - Provides detailed guidance on mechanical and other considerations when integrating DreamVu sensors into new and existing platforms