Only released in EOL distros:  

Package Summary

This package enables a 2D Hokuyo laser, connected to a Dynamixel servo motor, to produce a 3D point cloud that can be visualized in rviz and used to make an octomap.

Introduction

Light Detection and Ranging, or LiDAR, depends on data from one or more laser range finders. While some laser range finders are now available that create 3D scans, such as the Velodyne Puck, there are still gaps in the data, and 2D laser range finders provide even less data. By connecting a 2D sensor to a servo, the amount of data acquired can be significantly increased and improve the robot's perception of its environment. This package includes the code to operate such a setup and generates a point cloud that then be visualized in rviz or used to create an OctoMap.

Hardware

The hardware used for developing this package were based on the setup detailed in this capstone report from Glendale Community College.

  • UTM-30LX Hokuyo 2D laser scanner
  • MX-28 Dynamixel servo
  • Power adaptor and USB serial for servo
  • custom designed, 3D printed gimbal and mount

While this code is specifically designed to operate with the Hokuyo laser and Dynamixel servo, any laser range finder and servo that provide identical or similar data could be used with the proper modification of the code. The part files for the gimbal and mount used in this project are currently unavailable, but the original gimbal used in the capstone report can be found here.

Tutorial

This example walks through using this package and corresponding hardware for the first time. For additional information on the code, please see Nodes section below.

  1. sudo apt-get install ros-indigo-spin-hokuyo
  2. In the tutorials/launch folder, update the dynamixel_servos.yaml file to match the information for your servo. In particular, make sure the id number matches that of your servo.
  3. In the tutorials/launch folder, update the basic_motors.launch file, go to line 12. These parameters are used to set up the dynamixel_motor package. In particular, make sure the port_name and baud_rate match your servo. Also, check that your motor id falls within the inclusive range from min_motor_id to max_motor_id.
  4. Save and compile changes (if applicable).
  5. roslaunch spin_hokuyo basic_motors.launch
  6. In a new terminal, open the rostopics list. There should be two new commands: /tilt_controller/command and /tilt_controller/state. /command will issue new positions to the motor via Float64 (try this using rostopic pub). /state will list various pieces of information about the motor (rostopic echo).
  7. If this is fully functional, kill the node and run the following command. This should cause the motor to regularly sweep from 90 to -90 and generate a point cloud and occupancy map. Be sure to update the dynamixel_servos_tilting.yaml for position, speed, etc.
  8. roslaunch spin_hokuyo tilting_lidar_continuous.launch

Nodes

tilt_motor

Controls the motion of the servo, causing it to continuously sweep from -90 to +90 to -90.

Subscribed Topics

tilt_controller/state (dynamixel_msgs/JointState)
  • provides information on the position of the servo

Published Topics

tilt_controller/command (std_msgs/Float64)
  • tells servo new position (in radians) to move to
time/start_time (std_msgs/Time)
  • time that the servo begins a sweep
time/end_time (std_msgs/Time)
  • time that servo ends a sweep

Parameters

~maximum (integer, default: 92)
  • maximum angle, in degrees, servo can turn to
~minimum (integer, default: -92)
  • minimum angle, in degrees, servo can turn to
~pause (float, default: 0.1)
  • pause time between sending new commands to the servo, prevents grinding

tilt_motor_subscriber

Controls the motion of the servo, causing it to sweep from -90 to +90 to -90 when sent an empty message.

Subscribed Topics

tilt_controller/state (dynamixel_msgs/JointState)
  • provides information on the position of the servo
perform_sweep (std_msgs/Empty)
  • initializes a sweep

Published Topics

tilt_controller/command (std_msgs/Float64)
  • tells servo new position (in radians) to move to
time/start_time (std_msgs/Time)
  • time that the servo begins a sweep
time/end_time (std_msgs/Time)
  • time that servo ends a sweep

Parameters

~maximum (integer, default: 92)
  • maximum angle, in degrees, servo can turn to
~minimum (integer, default: -92)
  • minimum angle, in degrees, servo can turn to
~pause (float, default: 0.1)
  • pause time between sending new commands to the servo, prevents grinding

tilt_transform

Publishes the transforms between the laser scan and the servo.

Subscribed Topics

tilt_controller/State (dynamixel_msgs/JointState)
  • provides information on the position of the servo

Provided tf Transforms

servolaser
  • Aligns the laser scan in accordance with the angle of the servo at the time of the scan

hokuyo_robot_filter

Along with slightly limiting the angle of the Hokuyo, removes the robot from the scan data

Subscribed Topics

scan (sensor_msgs/LaserScan)
  • scan data collected by the Hokuyo

Published Topics

hokuyo_filtered (sensor_msgs/LaserScan)
  • scan data with points corresponding to robot removed

scan_to_pcl

Converts Hokuyo laser scan data to point cloud

Subscribed Topics

hokuyo_filtered (sensor_msgs/LaserScan)
  • scan data with points corresponding to robot removed

Published Topics

hokuyo_points (invalid message type for MsgLink(msg/type))
  • Hokuyo data without robot converted to point cloud

pcl_assembler_client

makes the service call to compile all transformed point clouds into one point cloud

Subscribed Topics

time/start_time (std_msgs/Time)
  • time that the servo begins a sweep
time/end_time (std_msgs/Time)
  • time that the servo ends a sweep

Published Topics

assembled_cloud (std_msgs/PointCloud2)
  • compiled cloud of all points from a single sweep

Services Called

assemble_scans2 (laser_assembler/AssembleScans2)
  • When an assembler receives an assemble_scans request, it searches its rolling buffer for clouds that occur in the requested interval (begin to end). These clouds are then assembled into a larger cloud, in the frame specified by the ~fixed_frame parameter, and sent to to the caller in the service response. This is a non-blocking operation and will return an empty cloud if no scans are received in the requested interval. The resulting cloud will have channels named intensities, index, distances, and stamps as defined by the laser_geometry::LaserProjection library. It returns a sensor_msgs/PointCloud2.

Parameters

~assembled_cloud_mode (string, default: subscriber)
  • sets node to either subscriber or time and causes node to either subscribe to specific sweep start and end times or compiles all scans in a particular amount of time
~scan_time (double, default: 5)
  • time interval from which scans are obtained to compile

Acknowledgements

This package was created as part of the Pinnacle Scholar program at Stevens Institute of Technology in the Robust Field Autonomy Laboratory. We would like to thank Prof. Brendan Englot and PhD students Shi Bai and Tixiao Shan for their assistance.

Wiki: spin_hokuyo (last edited 2017-07-27 19:55:24 by SarahBertussi)