Wiki

Only released in EOL distros:  

youbot_overhead_cameras: youbot_overhead_localization | youbot_overhead_vision

Package Summary

Vision software that can be used to locate a Kuka youBot and obstacles inside of a room based on two overhead cameras.

Nodes

image_calibration

image_calibration takes in two camera streams to create an occupancy map of the room and determine the position of a Kuka Youbot in that room. The class stitches the camera streams together and performs background extraction to locate obstacles. Color calibration files are used to locate key markers placed on the Kuka Youbot and the robot heading and position are published to 'position_from_camera' topic. The occupancy map is published to the 'image_cal' topic. The node handles both real Youbots and ones simulated in gazebo. The 'runFromSimulation' param marks the source of the camera feeds.

Subscribed Topics

/overhead_north/image_raw (sensor_msgs/Image) /overhead_south/image_raw (sensor_msgs/Image)

Published Topics

/image_calibration/position_from_camera (youbot_overhead_vision/PositionFromCamera) /image_calibration/image_cal (sensor_msgs/Image)

Parameters

/image_calibration/runFromSimulation (boolean) /image_calibration/floor_cal (string) /image_calibration/robot_lb_file (string) /image_calibration/robot_rb_file (string) /image_calibration/robot_lf_file (string) /image_calibration/robot_rf_file (string)

create_calibs

create_calibs allows users to easily create the calibration files used by the image_calibration node. The node creates a window with a camera feed from one of the overhead cameras. Color values can be added or removed from the different calibrations by using the mouse and keyboard commands, which are printed to the terminal. Calibration parameters, such as image blur and calibration accuracy, can be also modified using commands.

Subscribed Topics

/overhead_north/image_raw (sensor_msgs/Image) /overhead_south/image_raw (sensor_msgs/Image)

Parameters

/create_calibs/runFromSimulation (boolean) /create_calibs/real_floor_cal (string) /create_calibs/sim_floor_cal (string) /create_calibs/real_robot_lb_file (string) /create_calibs/sim_robot_lb_file (string) /create_calibs/real_robot_rb_file (string) /create_calibs/sim_robot_rb_file (string) /create_calibs/real_robot_lf_file (string) /create_calibs/sim_robot_lf_file (string) /create_calibs/real_robot_rf_file (string) /create_calibs/sim_robot_rf_file (string)

coord_conversion

coord_conversion contains conversions for various coordinate systems, including the overhead camera map, the occupancy grid, and the real-world coordinate systems. This node is used by nodes in both youbot_overhead_vision and rrl_localization.

Services

coord_conversion (youbot_overhead_vision/CoordConversion)

Startup

The youbot_overhead_vision package should be launched at the same time as the 'rrl_localization' package with the use of the 'path_planner.launch' or the 'path_planner_sim.launch" launch files depending on whether the camera streams are real or simulated. However, the node can be run on its own by using one of the following commands:

   1 rosmake youbot_overhead_vision
   2 roslaunch youbot_overhead_vision youbot_overhead_vision.launch

or

   1 rosmake youbot_overhead_vision
   2 roslaunch youbot_overhead_vision youbot_overhead_vision_sim.launch

With the above node running, you can test video streaming with the image_view package using the following command:

   1 rosrun image_view image_view image:="/image_calibration/image_cal"

You may find that the two camera images do not align properly due to different overhead camera positions. Changing this requires opening the 'image_calibration.h' and 'create_calibs.h' files, and changing the SIM_OVERLAP and REAL_OVERLAP constants to match your real or simulated camera streams overlaps.

You may also need to modify the calibration files. To do this, first change the useFromSimulation parameter found in the 'youbot_overhead_vision_create_calibs.launch' launch file to 'true' if the camera stream comes from gazebo, and 'false' otherwise. Then, run the calibration creation tool using the following commands:

   1 rosmake youbot_overhead_vision
   2 roslaunch youbot_overhead_vision youbot_overhead_vision_create_calibs.launch

The calibration tool allows for both calibrating points, and setting boundary regions through which the robot cannot drive through.

Wiki: youbot_overhead_vision (last edited 2012-11-06 13:07:18 by Russell Toris)