Skip to content

code-iai/pico_flexx_driver

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

61 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

PMD CamBoard pico flexx Driver

pixo_flexx_ros

Author

Maintainers

Table of contents

Description

This package is a ROS interface to the CamBoard pico flexx from pmd.

Features:

  • publishing point clouds, camera info, depth, ir and noise images on ROS topics
  • support for dynamic reconfigure
  • support for nodelets with zero copy transfers
  • a launch file with nodelet manager and machine tag support
  • optional static TF publisher

Dependencies

  • ROS Indigo or Kinetic (or newer should also work)
  • Royale SDK (recommended: latest version, at least 3.21)

Status

The driver has been tested on:

  • Ubuntu 14.04, 16.04, 18.04, 20.04
  • ROS Indigo, Kinetic, Melodic, Noetic

Install

  1. Install ROS: Instructions for Ubuntu 20.04

  2. Setup your ROS environment

  3. Download the royale SDK from https://pmdtec.com/picofamily/software/ and extract it

  4. Extract the archive that matches your kernel architecture from the extracted SDK to <catkin_ws>/src/pico_flexx_driver/royale. You can find out what your kernel architecture is by running uname -m.

    cd <catkin_ws>/src/pico_flexx_driver/royale
    unzip <path_to_extracted_royale_sdk>/libroyale-<version_number>-LINUX-x86-64Bit.zip   # uname -m = x86_64
    # or:
    unzip <path_to_extracted_royale_sdk>/libroyale-<version_number>-LINUX-arm-32Bit.zip   # uname -m = armv7l
    # or...
    
  5. Install the udev rules provided by the SDK

    cd <catkin_ws>/src/pico_flexx_driver/royale
    sudo cp libroyale-*/driver/udev/10-royale-ubuntu.rules /etc/udev/rules.d/
    
  6. Make sure that your user is in the plugdev group (you can use the command groups to check). If not, you need to add your user to the group:

    sudo usermod -a -G plugdev <your-user-name-here>
    

    Afterwards, you have to log out and log back in for the changes to take effect.

  7. Run catkin_make or catkin build (if you prefer catkin_tools)

  8. Plug in the CamBoard pico flexx device

  9. Run roslaunch pico_flexx_driver pico_flexx_driver.launch publish_tf:=true

  10. Start rosrun rviz rviz, set the Fixed frame to pico_flexx_link and add a PointCloud2 and select /pico_flexx/points

Note: The pico_flexx_driver automatically tries to use the most recent version that is extracted in <catkin_ws>/src/pico_flexx_driver/royale. To use a newer release just extract it to that directory in addition to the previous one and recompile it with catkin_make clean and catkin_make. If something does not work with a newer version, just delete the extracted directory and recompile it with catkin_make clean and catkin_make.

Usage

To start the pico flexx driver, please use the provided launch file:

roslaunch pico_flexx_driver pico_flexx_driver.launch

Parameters

The launch file has the following parameters:

  • base_name (default="pico_flexx"):

    Name of the node. All topics will be advertised under this name.

  • sensor (default=""):

    ID of the sensor that should be used. IDs of all connected devices are listed on startup.

  • use_case (default="0"):

    ID of the use case. A list of supported use cases is listed on startup.

  • automatic_exposure (default="true"):

    Enable or disable automatic exposure.

  • automatic_exposure_stream2 (default="true"):

    Enable or disable automatic exposure for stream 2.

  • exposure_time (default="1000"):

    Exposure time. Only for manual exposure.

  • exposure_time_stream2 (default="1000"):

    Exposure time for stream 2. Only for manual exposure.

  • max_noise (default="0.07"):

    Maximum allowed noise. Data with higher noise will be filtered out.

  • range_factor (default="2.0"):

    Range of the 16-Bit mono image which should be mapped to the 0-255 range of the 8-Bit mono image. The resulting range is range_factor times the standard deviation around mean.

  • queue_size (default="5"):

    Queue size for publisher.

  • publish_tf (default="false"):

    Publish a static TF transform for the optical frame of the camera.

  • base_name_tf (default="pico_flexx"):

    Base name of the tf frames.

  • machine (default="localhost"):

    Machine on with the nodes should run.

  • define_machine (default="true"):

    Whether the machine for localhost should be defined our not. Disable this if the launch file is included somewhere where machines are already defined.

  • nodelet_manager (default="pico_flexx"):

    Name of the nodelet manager.

  • start_manager (default="true"):

    Whether to start a nodelet manager our not. Disable this if a different nodelet manager should be used.

Dynamic reconfigure

Some parameters can be reconfigured during runtime, for example with rosrun rqt_reconfigure rqt_reconfigure. The reconfigurable parameters are:

  • use_case:

    Choose from a list of use cases.

  • exposure_mode, exposure_mode_stream2:

    AUTOMATIC or MANUAL.

  • exposure_time, exposure_time_stream2:

    Exposure time. Only for manual exposure.

  • max_noise:

    Maximum allowed noise. Data with higher noise will be filtered out.

  • range_factor:

    Range of the 16-Bit mono image which should be mapped to the 0-255 range of the 8-Bit mono image. The resulting range is range_factor times the standard deviation around mean.

Topics

When a mixed mode use case is selected, the second stream for all topics below is published under the stream2 namespace (e.g., /pico_flexx/stream2/points). In mixed mode, both a low-range, high-noise, high-frequency point cloud and a high-range, low-noise, low-frequency (5 Hz) point cloud are published. The 5 Hz point cloud in mixed mode only allows a maximum exposure time of 1300 microseconds, so it has slightly higher noise than the 5 Hz point cloud in single mode at 2000 microseconds.

/pico_flexx/camera_info

Bandwidth: 0.37 KB per message (@5 Hz: ~2 KB/s, @45 Hz: ~ 17 KB/s)

This topic publishes the camera intrinsic parameters.

/pico_flexx/image_depth

Bandwidth: 153.28 KB per message (@5 Hz: ~766 KB/s, @45 Hz: ~ 6897 KB/s)

This is the distorted depth image. It is a 32-Bit float image where each pixel is a distance measured in meters along the optical axis.

/pico_flexx/image_mono16

Bandwidth: 76.67 KB per message (@5 Hz: ~383 KB/s, @45 Hz: ~ 3450 KB/s)

This is the distorted IR image. It is a 16-Bit image where each pixel is an intensity measurement.

/pico_flexx/image_mono8