sbpl_3dnav_planner is a ROS wrapper for SBPL Full-Body Planner library to provide 3D navigation with full-body collision checking to move_base. It adheres to the nav_core::BaseGlobalPlanner interface specified in nav_core.
Source of SBPL Full-Body Planner:
(for ROS Electric only)
git clone https://sbpl.pc.cs.cmu.edu/redmine/people/mike/full-body-nav.git
Contents
Overview
The sbpl_3dnav_planner::Sbpl3DNavPlanner is a global planner that adheres to the nav_core::BaseGlobalPlanner interface found in the nav_core package and can be used as a global planner plugin for the move_base node. It performs three-dimensional full-body collision checking to compute paths that are collision-free with the environment.
The New Collision Model
The PR2 makes dancing look easy...
Sbpl3DNavPlanner
API Stability
- The ROS API is unreviewed.
- The C++ API is unreviewed.
ROS Topics
Subscribed Topics
collision_map_occ (arm_navigation_msgs/CollisionMap)- The 3D collision map needed for collision checking against the environment; required since the Costmap2D supplied by move_base is ignored
- The current status of all the joints of the robot
- Interface to allow individual insertion of collision objects into the 3D collision map
- Interface to allow insertion of attached collision objects into the robot's collision model
ROS Services
Services
/sbpl_full_body_planning/collision_check (sbpl_3dnav_planner/FullBodyCollisionCheck)- Service to perform collision checking using the robot's collision model and current view of the world
- Service to compute a set of collision-free robot poses from which the robot can reach a specified object
Services Called
<left_fk_service_name> (see params) (kinematics_msgs/GetPositionFK)- The service called to compute forward kinematics for the left arm
- The service called to compute forward kinematics for the right arm
ROS Parameters
~planner/search_mode (bool, default: true)
- Whether to stop after finding the first solution
- Amount of time to allow for planning (in seconds)
- TODO
- File describing the left arm; see package://sbpl_arm_planner/config/pr2_left_arm.cfg for details.
- File describing the right arm; see package://sbpl_arm_planner/config/pr2_right_arm.cfg for details.
- File describing the motion primitives allowed by the robot's arms
- File describing the motion primitives allowed by the robot's base
- TODO
- Whether to print the returned path to ROS_INFO; prints out joint angles and end effector poses for both arms and the (x, y, torso, theta) positions of the base
- Unused
- The time it takes to move between waypoints on the returned path
- Unused
- The URDF file for the robot
- The number of joints per arm
- The frame for the returned path and visualizations
- Name of the service call used to compute forward kinematics for the left arm
- Name of the service call used to compute inverse kinematics for the left arm
- Name of the service call used to compute forward kinematics for the right arm
- Name of the service call used to compute inverse kinematics for the right arm
- Whether to update the occupancy grid from the collision_map_occ topic
- The x offset from the right gripper's location to the object's location
- The y offset from the right gripper's location to the object's location
- The z offset from the right gripper's location to the object's location
- The x offset from the left gripper's location to the object's location
- The y offset from the left gripper's location to the object's location
- The z offset from the left gripper's location to the object's location
- The minimum distance away the robot will be from the object when using the /sbpl_full_body_planning/find_base_poses service
- The maximum distance away the robot will be from the object when using the /sbpl_full_body_planning/find_base_poses service (in meters)
- The number of angles to sample when using the /sbpl_full_body_planning/find_base_poses service; samples will be made uniformly from 0 to 2*pi
- The number of radii to sample when using the /sbpl_full_body_planning/find_base_poses service; samples will be made uniformly along the available workspace of the robot (obeying the maximum and minimum working distances parameters)
- Unused
- Whether to visualize the goal using PViz when the planner is called
- Whether to visualize the state expansions using AViz when the planner is called
- Whether to visualize the heuristic (the shortest path to the goal) using AViz when the planner is called
- Unused
- Whether to visualize the trajectory using PViz when the planner is called
- Whether to visualize the path the end effector takes using AViz when the planner is called
- Unused
- Whether to visualize the collision model of the robot
- Throttle for trajectory visualizations; e.g., a trajectory_throttle of 4 will make it so only every 4th pose will be displayed. Raise this to increase performance
- Whether to visualize the heuristic grid using AViz when the planner is called; no actual planning will be done if this is set