Introduction
The phoxi_camera driver provides a ROS interface for PhoXi devices.
Installation
Get the package from github and put it in your catkin workspace src folder:
$ cd ~/catkin_ws/src
$ git clone https://github.com/photoneo/phoxi_camera
ROS Node
Published Topics
The node can publish the received data through different topics:
/phoxi_camera/pointcloud (sensor_msgs/PointCloud2)
/phoxi_camera/confidence_map (
sensor_msgs/Image)
/phoxi_camera/normal_map (
sensor_msgs/Image)
/phoxi_camera/texture (
sensor_msgs/Image)
Parameters
The following parameters are supported:
~vertical_resolution (int)
- Desired vertical resolution of the camera image: [full resolution (1), half resolution (2)]
~horizontal_resolution (
int)
- Desired horizontal resolution of the camera image: [full resolution (1), half resolution (2)]
~scan_multiplier (
int)
- Defines the number of scans that will be taken and merged to single output.
~shutter_multiplier (
int)
- Multiplication of the Basic scanner shutter time.
~trigger_mode (
int)
- Defines the trigger mode of the device. Currently, only Freerun and Software Trigger are supported [Freerun (0), Software (1)]
~timeout (
int)
~confidence (
double)
~send_point_cloud (
bool)
- If enabled, an point cloud will be captured and published from the camera
~send_normal_map (
bool)
- If enabled, an normal map will be captured and published from the camera
~send_texture (
bool)
- If enabled, an texture will be captured and published from the camera
~send_confidence_map (
bool)
- If enabled, an confidence map will be captured and published from the camera
Testing
The point cloud published by the phoxi_camera node can be viewed with rviz.
roslaunch phoxi_camera phoxi_camera.launch