Only released in EOL distros:
Package Summary
A package containing localization software for use with the Kuka youBot in a room with two overhead cameras.
- Author: David Kent
- License: BSD
- Source: git https://github.com/WPI-RAIL/youbot_overhead_cameras.git (branch: fuerte-devel)
Contents
Nodes
path_planner
path_planner implements an actionlib server to plan paths for the robot base. The paths are planned by constructing a costmap with costmap2d and using the A* algorithm in navfn. Once a path is planned, it will be followed until the goal is reached, or until a new goal is given.Subscribed Topics
/base_localizer/pose_2d (youbot_overhead_localization/Pose2d)- The (x, y) position and heading of a robot base determined by the 'base_localizer' node
- A costmap used for path planning created by the 'planner_map_server' node based on information from overhead cameras
Published Topics
/cmd_vel (geometry_msgs/Twist)- The linear and angular velocities of the robot base
- The cost of the current point that the robot occupies, determined from the path planning costmap
Services
/path_planner/get_cost (youbot_overhead_localization/GetCost)- Returns the costmap cost at a specified point on the costmap
Parameters
/path_planner/runFromSimulation (boolean)- Determines whether the robot is operating in a simulated or real environment
base_localizer
base_localizer localizes the robot base using odometry and the overhead camera information acquired from the 'youbot_overhead_vision' package.Subscribed Topics
/image_calibration/position_from_camera (youbot_overhead_vision/PositionFromCamera)- The robot location and heading according to the overhead camera image
- The robot base odometry
Published Topics
/base_localizer/pose_2d (youbot_overhead_localization/Pose2d)- The (x, y) position and heading of the robot base
planner_map_server
planner_map_server is a modification of the map_server node written by Brian Gerkey from the ROS navigation stack to work with dynamic overhead maps.Subscribed Topics
/image_calibration/image_cal (sensor_msgs/Image)- The black and white occupancy grid image created by the 'image_calibration' node in the 'youbot_overhead_vision' package
Published Topics
/map (nav_msgs/OccupancyGrid)- The costmap from the overhead camera image used for path planning
- Contains the map metadata
Services
/static_map (nav_msgs/GetMap)- This service returns a deep copy of the map
Parameters
/planner_map_server/map_file_yaml ('string')- Location of the map metadata
- Location to save the map debug file
key_nav_safety
key_nav_safety bounds the speed of the robot when it is close to obstacles to ensure the robot does not get damaged.Subscribed Topics
/base_localizer/cost (youbot_overhead_localization/CostmapCost)- The costmap cost at the robot base's current location
- The pose of the robot base including (x, y) position and heading
- The requested linear and angular velocity for the robot base, pending safety checks
Published Topics
/cmd_vel (geometry_msgs/Twist)- Controls the robot's linear and angular velocity
Parameters
/path_planner/moveCommandTopic (string)- Contains the name of the topic through which move commands should be sent to the robot to control it. If the param is not set, '/cmd_vel' is assumed.
path_planner_client
path_planner_client Allows for the testing of path planning by creating an updateGoal service which can circumvent the need for creating an actionlib clientServices
/update_goal (youbot_overhead_localization/SetGoal)- the goal for the robot to plan a path to comprising of an (x, y) coordinate and the name of the camera feed topic that the point is located on
Startup
The youbot_overhead_localization package should be launched at the same time as the 'youbot_overhead_vision' 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_localization
2 roslaunch youbot_overhead_localization youbot_overhead_localization.launch
or
1 rosmake youbot_overhead_localization
2 roslaunch youbot_overhead_localization youbot_overhead_localization_sim.launch
The path planning itself normally requires a node to create an actionlib client to set path goals, but this can be avoided for testing purposes by launching the 'path_planner_client' node with the following command:
1 rosrun youbot_overhead_localization path_planner_client
This will create the /update_goal service, which can be called to set goals for the path planner.