DRC/UserGuide
DRCSim User Guide
DRCSim is a collection of models, environments, plugins, and tools that customize the Gazebo simulator for use in the DARPA Robotics Challenge (DRC). Gazebo contains general simulation capabilities and DRCSim includes the robots, objects, and code that are specific to the DRC. DRCSim is versioned and released independently of Gazebo. Releases are recorded in the change log and future plans are recorded in the roadmap.
Installation
Full installation instructions
Quickstart for binary installation on Ubuntu 12.04 (precise):
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu precise main" > /etc/apt/sources.list.d/ros-latest.list'
sudo sh -c 'echo "deb http://packages.osrfoundation.org/drc/ubuntu precise main" > /etc/apt/sources.list.d/drc-latest.list'
wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
wget http://packages.osrfoundation.org/drc.key -O - | sudo apt-key add -
sudo apt-get update
sudo apt-get install drcsim
Note that the first four steps are only needed the first time you install; after that, the apt-get calls are sufficient.
Setup
Before using DRCSim, you should configure your shell with the provided shell setup file
source /usr/share/drcsim/setup.sh
You must load this setup file in every shell from which you're using DRCSim. You may find it convenient to add the source line to your default shell configuration (e.g., ~/.bashrc).
No noise added.
Starting and stopping DRCSim
It's easiest to launch DRCSim using roslaunch. DRCSim includes several roslaunch files that bring up the simulator in various configurations (see below for details on each launch file).
Environment variables
The following environment variables affect the operation of DRCSim:
VRC_CHEATS_ENABLED: if this variable is set to1, then the development aids (aka cheats) listed below in the ROS API are enabled. Otherwise (including if the variable is not set to anything), the development aids are not enabled.- ROS environment variables
- Gazebo environment variables
Starting
To bring up the default DRCSim configuration (Atlas robot with no hands in an empty world):
roslaunch atlas_utils atlas.launch
Stopping
To stop the DRCSim after having launched it with roslaunch, press Ctrl-C in the terminal where you executed the roslaunch command. Shutting down can take several seconds; wait until you see that roslaunch has exited and returned to your shell prompt.
It's important to stop DRCSim in this way, by killing roslaunch. If you stop it in other ways (e.g., existing from the Gazebo GUI), you might leave other processes running that can cause problems with future simulation sessions.
Launch files
Listed below are roslaunch files with which users are recommended to experiment.
Unless noted otherwise, the simulation will start with gravity disabled for 10 seconds to allow the controllers to initialize; after that gravity is enabled and the robot is standing on the ground with full dynamics.
Launch file arguments
Unless otherwise noted, each launch file accepts the following roslaunch arguments:
gzname: which executable to invoke when running Gazebo. The default isgazebo, which brings up both the server and the GUI client. Other valid values are:gzserver, which brings up only the server (no GUI client; useful for running on remote machines and for testing) andgzclient, which only brings up the GUI client (rarely useful).gzworld: which.worldfile to pass to Gazebo on startup. The default varies with each launch file. For example, the default world foratlas_sandia_hands.launchisatlas_sandia_hands.world. This option is useful when you want the ROS configuration defined in a launch file but want to override the world file that's used.
E.g., to run the robot with Sandia hands without the client GUI (e.g., on a cloud machine):
roslaunch atlas_utils atlas_sandia_hands.launch gzname:=gzserver
General-purpose launch files
atlas_utils/launch/atlas.launch. This is the default configuration, useful for experimenting with the robot on its own.- Robot: Atlas with no hands
- Environment: empty world (just ground plane)
atlas_utils/launch/atlas_sandia_hands.launch. This is a simple environment that includes Atlas with the Sandia Hands.- Robot: Atlas with Sandia hands
- Environment: empty world (just ground plane)
atlas_utils/launch/atlas_drc_vehicle_fire_hose.launch. This environment includes Atlas, a drivable DRC Vehicle, and the standpipe for a firehose.- Robot: Atlas with Sandia hands
- Environment: ground plane with drivable DRC Vehicle and firehose standpipe.
- Tutorials: Using the VRC Plugin to tele-operate the DRC Vehicle, Using the VRC Plugin with Atlas and the DRC Vehicle
atlas_utils/launch/atlas_golf_cart_fire_hose.launch. This environment includes Atlas, a drivable golf cart, and the standpipe for a firehose.- Robot: Atlas with no hands
- Environment: ground plane with drivable golf cart and firehose standpipe.
- Tutorials: Using the VRC Plugin to tele-operate the Golf Cart, Using the VRC Plugin with Atlas and the Golf Cart
atlas_utils/launch/drc_sim_v0.launch. This contains a first draft of some elements of the VRC. None of these elements are final, but may be useful for experiments.- Robot: Atlas with no hands
- Environment: heightmap-based terrain, controllable golf cart, large building (power plant), hose and standpipe.
VRC Qualification launch files
atlas_utils/launch/qual_task_1.launch. The environment that will be used for VRC Qualification Task 1: walking.- Robot: Atlas with Sandia hands.
- Environment: Starting pen followed by a series of gates to walk through, progressing from flat ground to steps, ramps, and small obstacles.
atlas_utils/launch/qual_task_2.launch. The environment that will be used for VRC Qualification Task 2: manipulation.- Robot: Atlas with Sandia hands.
- Environment: Table with cordless drill that is to be moved into a bin.
- Note: The robot's hip joint is pinned to the world, removing the need to balance.
atlas_utils/launch/qual_task_3.launch. The environment that will be used for VRC Qualification Task 3: ??.- Robot: Atlas with Sandia hands.
- Environment: ??
atlas_utils/launch/qual_task_4.launch. The environment that will be used for VRC Qualification Task 4: ??.- Robot: Atlas with Sandia hands.
- Environment: ??
VRC launch files
atlas_utils/launch/vrc_task_1.launch. An environment of the type that will be used for VRC Task 1: driving.- Robot: Atlas with Sandia hands.
- Environment: Starting pen followed by utility vehicle that must be driven along a road.
atlas_utils/launch/vrc_task_2.launch. An environment of the type that will be used for VRC Task 2: walking.- Robot: Atlas with Sandia hands.
- Environment: Starting pen followed by a series of gates to walk through, progressing from flat ground increasingly challenging terrain.
atlas_utils/launch/vrc_task_3.launch. An environment of the type that will be used for VRC Task 3: manipulation.- Robot: Atlas with Sandia hands.
- Environment: Table with a hose that is to be connected to a spigot.
ROS APIs
The DRC Simulation exposes a set of ROS APIs for users to develop with. Doxygen documentation can be found in the DRCSim API page.
Published topics
The following data are published by the DRC Simulator.
| Name | Type | Rate | Description |
| System | |||
|---|---|---|---|
| /clock | rosgraph_msgs/Clock | Once per physics update, default 1000 Hz | The current simulation time. |
| /rosout | rosgraph_msgs/Log | Varies | Log messages from various parts of the system. |
| /rosout_agg | rosgraph_msgs/Log | Varies | Log messages from various parts of the system, aggregated into fewer messages for more efficient transmission. |
| /tf | tf/tfMessage | Varies | Coordinate transforms from various parts of the system. See the tf documentation. |
| /tf_static /tf2_buffer_server/* |
Various | Varies | Topics offered by tf2_buffer_server, part of tf2_ros. Experimental. |
| /vrc_score | atlas_msgs/VRCScore | 1 Hz | Unofficial score data from the currently running task. Only published when using VRC practice or final worlds. |
| /vrc/bytes/remaining/downlink /vrc/bytes/remaining/uplink |
std_msgs/String | 1 Hz | How many downlink/uplink bytes remain for the currently running task. Only published when running in the practice or competition configuration, using cloud computing resources (it's published by the vrc_netwatcher, which runs on the router). |
| Atlas | |||
| /atlas/controller_statistics | atlas_msgs/ControllerStatistics | 1 Hz | Timing information about the per-joint controllers, for debugging. This message tells you the age of the command messages received on /atlas/joint_commands, where the age of a message foo is equal to (current simulation time - foo.header.timestamp). The easiest way to make use of this debugging mechanism is to, in your ROS controller node, set header.timestamp on each outgoing command message on /atlas/joint_commands to the value of header.timestamp that was included in the most recent state message that you received on /atlas/joint_states. Then the age data is measuring, from the per-joint controllers' perspective, the round-trip time between publishing a state message and receiving a command message that responds to that state message. See an example. |
| /atlas/force_torque_sensors | atlas_msgs/ForceTorqueSensors | Once per physics update, default 1000 Hz | Data from the force-torque sensors on the feet (3-axis: z-linear force, x and y-axis torques. The remaining axis values are zeros.) and wrists (full 6-axis feedback). No noise added. |
| /atlas/imu | sensor_msgs/Imu | Once per physics update, default 1000 Hz | Data from the IMU in the robot's torso. As of DRCSim 2.2.x, no noise added. |
| /atlas/joint_states | sensor_msgs/JointState | Once per physics update, default 1000 Hz | The current state of the robot's joints (not including the sensor head or hands). No noise added. |
| /atlas/atlas_state | atlas_msgs/AtlasState | Once per physics update, default 1000 Hz | Changed in DRCSim 2.3.0. The current state of the robot; combines the data from /atlas/joint_states, /atlas/imu, and /atlas/force_torque_sensors. Note that the contents of the message changed with drcsim 2.3; the changes were made to make the message smaller than 1500 bytes to accommodate transport via UDP. Also, the topic name changed from /atlas/atlas_states to /atlas/atlas_state. |
| /atlas/atlas_sim_interface_state | atlas_msgs/AtlasSimInterfaceState | 250 Hz | New in DRCSim 2.4.0. State of the BDI behavior library. |
| /atlas/synchronization_statistics | atlas_msgs/SynchronizationStatistics | 1000 Hz | New in DRCSim 2.6.0. Data on the controller synchronization system. Only published if the most recently received command via /atlas/atlas_command includes a non-zero value for the desired_controller_period_ms field, indicating that synchronization has been requested (see the synchronization tutorial) |
| Multisense-SL sensor head [1] | |||
| /multisense_sl/imu | sensor_msgs/Imu | Once per physics update, default 1000 Hz | Data from the IMU in the robot's head. Zero-mean Gaussian noise and random bias added in DRCSim 2.3.0. |
| /multisense_sl/joint_states | sensor_msgs/JointState | Once per physics update, default 1000 Hz | The current state of the head's joint (the laser spindle). No noise added. |
| /multisense_sl/laser/scan | sensor_msgs/LaserScan | Throttled at 40 Hz | Data from the laser rangefinder in the robot's head. Zero-mean Gaussian noise added in DRCSim 2.3.0. |
| /multisense_sl/camera/left/image_raw | sensor_msgs/Image | Default at 30Hz, adjustable between 1 to 30Hz. | Images from the left camera in the robot's head. Zero-mean Gaussian noise added in DRCSim 2.3.0. |
| /multisense_sl/camera/left/camera_info | sensor_msgs/CameraInfo | Same as corresponding /multisense_sl/camera/left/image_raw. | Metadata from the left camera in the robot's head. More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. No noise added. |
| /multisense_sl/camera/right/image_raw | sensor_msgs/Image | Default at 30Hz, adjustable between 1 to 30Hz. | Images from the right camera in the robot's head. Zero-mean Gaussian noise added in DRCSim 2.3.0. |
| /multisense_sl/camera/right/camera_info | sensor_msgs/CameraInfo | Same as corresponding /multisense_sl/camera/right/image_raw. | Metadata from the right camera in the robot's head. More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. No noise added. |
| /multisense_sl/camera/(various) | See stereo_image_proc | Approximately less than 10Hz (limited by CPU load). | Camera data from the robot's head is fed into stereo_image_proc, which in turn publishes various topics. For more details on the various parameters and topics published by the stereo_image_proc, please see stereo_image_proc documentation. |
| Sandia hands | |||
| /sandia_hands/l_hand/joint_states | sensor_msgs/JointState | Once per physics update, default 1000 Hz | The current state of the joints in the robot's left hand. No noise added. |
| /sandia_hands/l_hand/imu | sensor_msgs/Imu | Once per physics update, default 1000 Hz | Data from the IMU in the robot's left hand. Noise and bias added in DRCSim 2.3.1. |
| /sandia_hands/l_hand/tactile_raw | sandia_hand_msgs/TactileRaw | Once per physics update, default 1000 Hz | New in DRCSim 2.6.0. Data from the tactile arrays in the robot's left hand. No noise added. See this spec sheet for tactile sensor locations on the hand |
| /sandia_hands/l_hand/camera/left/image_raw | sensor_msgs/Image | Default at 30Hz, not adjustable. | New in DRCSim 2.3.0. Images from the right camera in the robot's left hand. Zero-mean Gaussian noise added. |
| /sandia_hands/l_hand/camera/left/camera_info | sensor_msgs/CameraInfo | Same as corresponding image topic (/sandia_hands/l_hand/camera/left/image_raw) | New in DRCSim 2.3.0. Metadata from the right camera in the robot's left hand. More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. |
| /sandia_hands/l_hand/camera/right/image_raw | sensor_msgs/Image | Default at 30Hz, not adjustable. | New in DRCSim 2.3.0. Images from the right camera in the robot's right hand. Zero-mean Gaussian noise added. |
| /sandia_hands/l_hand/camera/right/camera_info | sensor_msgs/CameraInfo | Same as corresponding image topic (/sandia_hands/l_hand/camera/right/image_raw) | New in DRCSim 2.3.0. Metadata from the right camera in the robot's right hand More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. |
| /sandia_hands/l_hand/camera/(various) | See stereo_image_proc | Approximately less than 10Hz (limited by CPU load). | New in DRCSim 2.3.1. Camera data from the robot's left hand is fed into stereo_image_proc, which in turn publishes various topics |
| /sandia_hands/r_hand/joint_states | sensor_msgs/JointState | Once per physics update, default 1000 Hz | The current state of the joints in the robot's right hand. No noise added. |
| /sandia_hands/r_hand/imu | sensor_msgs/Imu | Once per physics update, default 1000 Hz | Data from the IMU in the robot's right hand. Noise and bias added in DRCSim 2.3.1. |
| /sandia_hands/r_hand/tactile_raw | sandia_hand_msgs/TactileRaw | Once per physics update, default 1000 Hz | New in DRCSim 2.6.0. Data from the tactile arrays in the robot's right hand. No noise added. See this spec sheet for tactile sensor locations on the hand |
| /sandia_hands/r_hand/camera/left/image_raw | sensor_msgs/Image | Default at 30Hz, not adjustable. | New in DRCSim 2.3.0. Images from the right camera in the robot's right hand. Zero-mean Gaussian noise added. |
| /sandia_hands/r_hand/camera/left/camera_info | sensor_msgs/CameraInfo | Same as corresponding image topic (/sandia_hands/r_hand/camera/left/image_raw) | New in DRCSim 2.3.0. Metadata from the left camera in the robot's right hand. More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. |
| /sandia_hands/r_hand/camera/right/image_raw | sensor_msgs/Image | Default at 30Hz, not adjustable. | New in DRCSim 2.3.0. Images from the right camera in the robot's right hand. Zero-mean Gaussian noise added. |
| /sandia_hands/r_hand/camera/right/camera_info | sensor_msgs/CameraInfo | Same as corresponding image topic (/sandia_hands/r_hand/camera/right/image_raw) | New in DRCSim 2.3.0. Metadata from the right camera in the robot's right hand More details on the components of the sensor_msgs/CameraInfo message can be found in CameraInfo Documentation. |
| /sandia_hands/r_hand/camera/(various) | See stereo_image_proc | Approximately less than 10Hz (limited by CPU load). | New in DRCSim 2.3.1. Camera data from the robot's right hand is fed into stereo_image_proc, which in turn publishes various topics |
| Development aids (not available during competition) | |||
| /atlas/debug/l_foot_contact, /atlas/debug/r_foot_contact |
geometry_msgs/WrenchStamped | Once per physics update, default 1000 Hz | Contact forces and torques on the left foot (l_foot_contact) and right foot (r_foot_contact) of Atlas |
| /drc_vehicle/brake_pedal/state, /golf_cart/brake_pedal/state |
std_msgs/Float64 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current brake pedal state from 0 (no brake applied) to 1.0 (100% braking applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/direction/state, /golf_cart/direction/state |
std_msgs/Int8 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current state of direction switch with -1: Reverse, 0: Neutral, 1: Forward. See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/gas_pedal/state, /golf_cart/gas_pedal/state |
std_msgs/Float64 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current gas pedal state from 0 (no gas applied) to 1.0 (100% gas applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/hand_brake/state, /golf_cart/hand_brake/state |
std_msgs/Float64 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current hand brake state from 0 (no brake applied) to 1.0 (100% braking applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/hand_wheel/state, /golf_cart/hand_wheel/state |
std_msgs/Float64 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current angle of the steering hand wheel in radians. See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/key/state, /golf_cart/key/state |
std_msgs/Int8 | 20 Hz (set in ros/atlas_msgs/ DRCVehicleROSPlugin.cpp) | Current state of key switch with 0: Off, 1: On, -1: Error state requiring direction switch to be placed in Neutral before gas torque can be applied. See the drc_vehicle tutorial and golf_cart tutorial. |
| /ground_truth_odom | nav_msgs/Odometry | 100 Hz (specified in ros/atlas_description /urdf/atlas.gazebo) | Ground truth pose of atlas pelvis. |
Notes:
- [1] The physical Multisense-SL device has some limitations regarding how many streams of data it can provide simultaneously due to available network bandwidth. drcsim does not implement the corresponding logic to provide matching behavior. If you want to ensure that your code will transfer directly to hardware, you should live within the constraints of the hardware when working in simulation. Having said that, it is likely that drcsim will provide smaller images, at a lower frame rate than the physical device because of CPU limitations in stereo processing (the physical device does stereo in an FPGA and so does not suffer from this limitation).
Subscribed topics
The following commands are subscribed by the DRC Simulator.
| Name | Type | Description |
| Atlas | ||
|---|---|---|
| /atlas/control_mode | std_msgs/String | Control mode for Boston Dynamics Behavior Library (copied from documentation here)
NOTE This mode will be limited, please use the `/atlas/atlas_sim_interface_command` and `/atlas/atlas_sim_interface_state` topics for interfacing with Boston Dynamics Behavior Library. |
| /atlas/atlas_command | atlas_msgs/AtlasCommand | New in DRCSim 2.3.0. Command data to the Atlas robot. No noise added. This topic, instead of `/atlas/joint_commands`, is recommended for use by controllers that wish to operate at a higher update rate with simulation. It is specifically designed to be less than 1500 bytes, so as to be amenable to transport via UDP. |
| /atlas/atlas_sim_interface_command | atlas_msgs/AtlasSimInterfaceCommand | New in DRCSim 2.4.0. Interface to send commands to the BDI behavior library. |
| /atlas/joint_commands | osrf_msgs/JointCommands | Setpoints and gains for the robot's joints (not including the sensor head or hands), see Atlas control tutorial with C++ and Atlas control tutorial with python. |
| Multisense-SL sensor head | ||
| /multisense_sl/set_spindle_speed | std_msgs/Float64 | Desired velocity, in radians/second, of the spindle holding the laser rangefinder (set to 0 to stop rotation) |
| /multisense_sl/fps | std_msgs/Float64 | Not yet implemented. Desired image capture rate, in frames per second. |
| Sandia hands | ||
| /sandia_hands/l_hand/joint_commands /sandia_hands/r_hand/joint_commands |
osrf_msgs/JointCommands | Setpoints and gains for the joints in the robot's left hand (l_hand) and right hand (r_hand) |
| /sandia_hands/l_hand/simple_grasp /sandia_hands/r_hand/simple_grasp |
sandia_hand_msgs/SimpleGrasp | Command simple grasps to left hand (l_hand) and right hand (r_hand). Valid values for the name field are: "cylindrical", "spherical", and "prismatic". No guarantees are provided about the capabilities of these grasps. |
| Development aids (not available during competition) | ||
| /atlas/cmd_vel | geometry_msgs/Twist | Move atlas around as if it were wheeled robot, without walking or balancing ( see this tutorial) |
| /atlas/configuration | sensor_msgs/JointState | Not currently implemented. |
| /atlas/set_pose | geometry_msgs/Pose | Teleport the robot with the current configuration to the desired pose (relative to the pelvis). For example, `rostopic pub /atlas/set_pose --once 'geometry_msgs/Pose' '{position: {z: 0.95}, orientation: {w: 1}}'` will return the robot approximately to the starting point. |
| /joint_trajectory | trajectory_msgs/JointTrajectory | Disables physics and animates a robot by playing back a joint trajectory (see tutorial). |
| /atlas/mode | std_msgs/String | Set atlas mode: "nominal" (normal), "no_gravity" (robot floats), "pinned" (pin the hip joint to the world, turn off gravity), "pinned_with_gravity" (pin the hip, turn on gravity), "feet" (pin the feet to the ground), "harnessed" (similar to "pinned"). |
| /atlas/debug/test | atlas_msgs/Test | /tmp/qual_task_1For internal testing. Do not use. |
| /atlas/debug/sync_delay | std_msgs/String | For internal testing. Do not use. |
| /atlas/apply_pelvis_force | geometry_msgs/Wrench | New in 2.4.0. Apply a force to the pelvis. |
| /atlas/pause | std_msgs/String | New in 2.4.0. For internal testing. Do not use. |
| /drc_world/robot_enter_car | geometry_msgs/Pose | Teleport and pin the robot to the driver's seat of the Golf Cart or DRC Vehicle if the appropriate world is loaded. The pose specifies an offset from the default seated position. See the Golf Cart with Atlas tutorial and the DRC Vehicle with Atlas tutorial. |
| /drc_world/robot_exit_car | geometry_msgs/Pose | Unpin the robot from the driver's seat and teleport to the driver's side door of the Golf Cart or DRC Vehicle if the appropriate world is loaded. The pose specifies an offset from the default location near the driver's side door. See the Golf Cart with Atlas tutorial and the DRC Vehicle with Atlas tutorial. |
| /drc_world/robot_grab_link | geometry_msgs/Pose | Pin the fire hose link to the right hand of atlas if the appropriate world is loaded. The pose argument is currently ignored. |
| /drc_world/robot_release_link | geometry_msgs/Pose | Unpin the fire hose link from the right hand of atlas if the appropriate world is loaded. The pose argument is currently ignored. |
| /drc_vehicle/brake_pedal/cmd /golf_cart/brake_pedal/cmd |
std_msgs/Float64 | Set brake pedal command from 0 (no brake applied) to 1.0 (100% braking applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/direction/cmd /golf_cart/direction/cmd |
std_msgs/Int8 | Set direction switch with -1: Reverse, 0: Neutral, 1: Forward. Direction switch defaults to Forward. This development aid is currently the only way to set the direction switch of the vehicle. See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/gas_pedal/cmd /golf_cart/gas_pedal/cmd |
std_msgs/Float64 | Set gas pedal command from 0 (no gas applied) to 1.0 (100% gas applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/hand_brake/cmd /golf_cart/hand_brake/cmd |
std_msgs/Float64 | Set hand brake command from 0 (no brake applied) to 1.0 (100% braking applied). See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/hand_wheel/cmd /golf_cart/hand_wheel/cmd |
std_msgs/Float64 | Set desired angle of the steering hand wheel in radians. See the drc_vehicle tutorial and golf_cart tutorial. |
| /drc_vehicle/key/cmd /golf_cart/key/cmd |
std_msgs/Int8 | Set key switch with 0: Off, 1: On. Note that the direction switch must be in Neutral when the key is turned on or an error will result. The key defaults to On. This development aid is currently the only way to set the key switch of the vehicle. See the drc_vehicle tutorial and golf_cart tutorial. |
ROS Services
The following ROS services are subscribed to by the DRC Simulator.
| Name | Type | Description | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| Atlas | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
| /atlas/reset_controls | atlas_msgs/ResetControls | Reset various parts of the controllers' internal state. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /atlas/set_joint_damping | atlas_msgs/SetJointDamping | New in DRCSim 2.6.0. Set viscous joint damping coefficients for Atlas. Input array damping_coefficients must have 28 elements, one per joint, and the order of joints can be found in atlas_msgs/AtlasState. Damping coefficient limits and default values for each joint are listed below:
|
||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /atlas/get_joint_damping | atlas_msgs/GetJointDamping | New in DRCSim 2.6.0. Get viscous joint damping coefficients for Atlas. Resulting array of damping_coefficients has 28 elements, one per joint, and the order of joints can be found in atlas_msgs/AtlasState | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /atlas/atlas_filters | atlas_msgs/AtlasFilters | New in DRCSim 2.6.0. Control position and/or velocity filtering (implemented in a plugin running inside simulation at 1KHz). | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| Multisense-SL sensor head | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /multisense_sl/camera/(various) | See stereo_image_proc | Various dynamic_reconfigure services are provided to allow configuration of stereo image processing. For more details on the various parameters and services offered by the stereo_image_proc, please see stereo_image_proc documentation. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| Sandia hands | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /sandia_hands/set_joint_damping | atlas_msgs/SetJointDamping | Set viscous joint damping coefficients for both robot's left hand (l_hand) and right hand (r_hand). The first 24 of the 28 element-long input array damping_coefficients are used, one per joint, and the order of joints can be found here. Joint damping coefficients can be in the range of 1.0 Nms/rad to 30.0 Nms/rad. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /sandia_hands/get_joint_damping | atlas_msgs/GetJointDamping | Get viscous joint damping coefficients for both robot's left hand (l_hand) and right hand (r_hand). The first 24 of the 28 element-long damping_coefficients will be filled, one per joint, and the order of joints can be found here. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /sandia_hands/l_hand/simple_grasp /sandia_hands/r_hand/simple_grasp |
sandia_hand_msgs/SimpleGraspSrv | Command simple grasps to left hand (l_hand) and right hand (r_hand). Valid values for the name field are: "cylindrical", "spherical", and "prismatic". No guarantees are provided about the capabilities of these grasps. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| Development aids (not available during competition) | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /gazebo/pause_physics | std_msgs/Empty | Pauses Gazebo. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /gazebo/unpause_physics | std_msgs/Empty | Unpauses Gazebo. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /gazebo/reset_simulation | std_msgs/Empty | Resets simulation. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
| /gazebo/reset_models | std_msgs/Empty | Resets model poses in Gazebo. | ||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
Controllers
Note: Under construction, details may change drastically in the next few iterations.
Atlas Per-Joint Servo Controllers
At the lowest level, on every simulation update at 1kHz, joint torque is computed based on the following formula:
effort_commanded =
k_effort * (
kp_position * ( position - measured_position ) +
ki_position * 1/s * ( position - measured_position ) +
kd_position * s * ( position - measured_position ) +
kp_velocity * ( velocity - measured_velocity ) +
effort ) +
(1 - k_effort) * effort_bdi_controller
In addition, integral tie-back (TODO) is also being enforced on the resulting force commands.
Boston Dynamics Atlas Simulation Behavior Library (AtlasSimInterface)
The AtlasSimInterface library populates the feed-forward force command (effort_bdi_controller) in the per-joint controllers. See Controller ROS API section for hooks to call into the behavior library.
Updates regarding release state and available behaviors will be detailed in the ChangeLog and RoadMap.
There is some initial API documentation for the underlying behavior library. The ROS interface is a pretty thin wrapper around the C++ library API.
AtlasSimInterface Behaviors
Behaviors are controller states that govern which joints are controller-governed, and which are user-governed. The neck joint, unless otherwise stated, is user-controlled.
Behavior changes are controlled by publishing to the 'atlas_sim_interface_command' topic, or are controlled automatically. Examples of automatic changes include switching to Freeze when the robot starts to fall or reverting to stand if enough steps weren't provided in the walk behavior. Sometimes, a requested behavior will not be possible as determined by the controller and will be ignored.
- User: All joints controlled by performer (through the per-joint servo controllers).
- Stand: Statically stable stand. This is the "hub" mode, entry and termination into other behaviors.
- Walk: Dynamically stable walking using approximate step locations.
- Step: Slow walking with precise step locations, statically stable between steps.
- Manipulate: Statically stable stand, but with upper body joints available for performer control to enable tool use and environment interaction.
- Freeze: For falling, when other behaviors have no chance of working.
- StandPrep: Initialization behavior for entering Stand.
Stand
Stand is a statically stable stand, and the robot will attempt to maintain balance in light of small pushes, inclines, or other applied forces.
The Stand behavior is the central behavior, and all behavior transitions, except to User and Freeze, occur through Stand. To enter stand, the robot must be mostly upright with no appreciable linear or angular velocity. For simulation startup, StandPrep puts the robot into a suitable configuration.
Walk
Walk is a dynamic walking behavior that is robust to small ground height and slope disturbances.
A walk command in the 'Command' message requires four steps specified in 'walk_params.step_queue' with the following:
- step_index: Which step in the Walk this step data is for.
- foot_index: Which foot (0 for left, 1 for right). Will switch to Stand mode if two consecutive steps specify the same foot.
- duration: How long the step should take.
- pose: Where to put the foot, in Atlas world frame. Only yaw is used from the orientation quaternion.
The controller requires a queue of four steps to execute a stable walk. As few as two steps may be used, but it will be less stable and may switch to a Stand behavior. The step_queue can be re-specified while the current queue is executed, but it may result in instability. The next four steps needed of a longer trajectory can be determined by observing the 'walk_feedback.next_step_index_needed' field of the 'atlas_sim_interface_state' topic.
Once a foot has been lifted, the step pose cannot be changed. The Walk behavior will do its best to follow the step data, but it may have to modify steps to fit within constraints, or maintain stability. Observing the 'walk_feedback.step_queue_saturated' in the 'atlas_sim_interface_state' can provide insight into whether a trajectory should be replanned.
Step
Step is a quasi-static walking behavior that will realize better foot placement accuracy than walk, but is still subject to kinematic constraints.
A step command is specified in the 'step_params.desired_step' of the 'Command' message. If the controller modifies a step to meet constraints, feedback will be provided in the 'step_feedback.desired_step_saturated' of the 'State' message.
The Step behavior has two states that are specified in 'step_feedback.status_flags' of the 'State' message. The step_data in 'desired_step' can be changed when it enters the STEP_SUBSTATE_SWAYING sub-state.
Manipulate
Manipulate is similar to stand, except it makes more joints available for user control. The user must set the pelvis orientation, height, and position relative to the center of the feet. The user can control the movement of the back and upper body joints. The controller will be robust to added masses likely to occur during manipulation situations.
Extreme, or quick moves can overwhelm the controller's ability to maintain stability. It is also recommended that the feet be placed with step commands into strong, and stable positions.
Freeze
Behaviors automatically enter the Freeze state when it is determined that the robot has entered an unrecoverable state. It prevents the controller from becoming unstable.
StandPrep
StandPrep is a special case behavior that assumes the robot is in a 'harnessed' state. It moves the joints into a position that is suitable for stand when gravity is turned on.
Foot Reference Frames
Foot points indicated by foot_pos_est are offset (0.06 0.0 -0.085) meters (x y z) in the foot frame for both left/right feet. This value is subject to change (though we have no plans to do so at the moment.)
Controller ROS API
The ROS API provides four key topics that are expected to be used in controlling the Atlas robot:
/atlas/atlas_state: This topic provides the user with the current state of all joints, IMU and force torque sensors./atlas/atlas_command: This topic provides set-points and gains for a set of low-level PID controllers that operate on a per-joint basis. (This is a slight extension to/atlas/joint_commandwith addition of PID coefficients, see the message documentation for the control law that is implemented). Users are expected to write higher-level behavior as ROS nodes that command these per-joint controllers to achieve coordinate motion such as balancing and walking./atlas/atlas_sim_interface_command: The AtlasSimInterface Behavior Library control command can be issued over this ROS topic./atlas/atlas_sim_interface_state: Example high-level behavior control can be seen in this tutorial, which utilizes an underlying demo actionlib server that closes the loop on/atlas/atlas_sim_interface_commandand/atlas/atlas_sim_interface_state.
Controller Blending
Parameter k_effort can be used to switch / blend controller torques from AtlasCommand and AtlasSimInterfaceCommand. Please see the Control Mode Switching Tutorial for more details on how to switch between servo control mode and AtlasSimInterface Behavior Library control mode.
Update Rates
Regarding update rates, we currently expect that:
- the simulation timestep will be 0.001s (1ms);
- the update rate for the per-joint controllers running inside Gazebo (the sink for the
/atlas/joint_commandstopic) will be 1KHz (i.e., they will update every simulation timestep); and - users will be able to write controllers external to simulation, as ROS nodes, that interact with the per-joint controllers at 200Hz-500Hz (we will narrow this range as we can with performance data).
Control Strategies
Regarding control strategies:
- to implement conventional PID control, set the commanded effort to zero;
- to implement torque control, set the PID gains to zero (and presumably set the commanded effort to non-zero); and
- to mix PID control and torque control, command non-zero PID gains and non-zero effort (the resulting torques will be summed).
Sandia hands
Control of the Sandia hands is expected to be similar to control of Atlas. Any expected differences will be documented here.
Qualifications
Extra instructions for late Qualification
IMPORTANT: For teams doing qualifying runs on or after May 17th, 2013, extra steps are required to get your system configured to use the right versions of software and models (the released versions have been updated in preparation for Practice and Competition).
Installation: download and manually install specific versions of the code (assuming here that you're working on 64-bit Ubuntu 12.04 (Precise)):
# Install with apt-get to resolve dependencies, then uninstall sudo apt-get update sudo apt-get install -y drcsim sudo apt-get remove -y drcsim gazebo osrf-common sandia-hand # Download specific versions wget http://gazebosim.org/assets/distributions/osrf-common_1.0.6-1~precise_amd64.deb wget http://gazebosim.org/assets/distributions/sandia-hand_5.1.13-1~precise_amd64.deb wget http://gazebosim.org/assets/distributions/gazebo_1.7.3-1~precise_amd64.deb wget http://gazebosim.org/assets/distributions/drcsim_2.5.2-1~precise_amd64.deb # Manually install with dpkg sudo dpkg -i gazebo_1.7.3-1~precise_amd64.deb sudo dpkg -i osrf-common_1.0.6-1~precise_amd64.deb sudo dpkg -i sandia-hand_5.1.13-1~precise_amd64.deb sudo dpkg -i drcsim_2.5.2-1~precise_amd64.deb # Remove any cached models rm -rf ~/.gazebo/models
Configuration: point Gazebo at the archived version of the online model database (do this in every shell you use):
# Usual setup . /usr/share/drcsim/setup.sh # Use a special archive of models export GAZEBO_MODEL_DATABASE_URI=http://gazebosim.org/models_vrc_quals/
Software Versions
Gazebo 1.7.3
DRC Sim 2.5.2
Sandia Hands 5.1.13
OSRF Common 1.0.6
CloudSim is not used for Qualification.
Creating a Qualification Submission
Step 1: Record the operator and display videos
Record the operator and display videos following the procedure detailed in the Video Guide.
Step 2: Start a Qualification Task
Important: Data is stored in /tmp/qual_task_{n}, where {n} is the number of the Qualification task. Old data will be overwritten. Make sure to backup your data between runs.
Launch one of the Qualification tasks using a ROS launch file.
Step 3: Perform the Run
Using some combination of teleoperation and autonomy, achieve the task. When you're happy with the run, move onto the next step. The simulation will not stop automatically on task completion.
Step 4: Stop a Qualification Task
Stop logging
gzlog stop
The simulation will be paused while the buffered log data is flushed and written to the log file. This can take a very long time. In our testing, it can take about as long as the time required for the simulation itself. Once the log file is finished writing, the simulation will resume.
Wait until the last line in the
state.logfile is</gazebo_log>. This can be verified with:$ tail -n 1 -f /tmp/qual_task_1/state.log </gazebo_log>$
Quit Simulation using ctrl-c
Step 5: Verify the output
Verify the existence of two files upon completion of a Qualification task.
- A Gazebo state log file, called
state.logshould exist in/tmp/qual_task_{n}/, where {n} is the number of the Qualification task. - A Qualification score file, called
score.logshould exist in/tmp/qual_task_{n}/, where {n} is the number of the Qualification task.
Step 6: Validate the output
Replay the Gazebo state log file. This will make sure that the data is valid.
gazebo -p /tmp/qual_task_{n}/state.logInspect the score log file by opening it in your favorite editor.
gedit /tmp/qual_task_{n}/score.logThe contents will contain a header that describes the data. Make sure the data is correct.
Step 7: Create a zip file for log submission
Run the mkqual.bash script with three command line arguments:
- The number of the Qualification task: 1, 2, 3 or 4
- The Gazebo state log file:
/tmp/qual_task_{n}/state.log - The score log file:
/tmp/qual_task_{n}/score.log
Example:
mkqual.bash 1 /tmp/qual_task_1/state.log /tmp/qual_task_1/score.log
Note that this script may take 5 minutes / 100 MB in state.log.
A new file will be created in your current directory called vrc_qual_{n}.zip.
Unzipping this log file should produce the state.log and score.log files.
Step 8: Upload the zip log file to the VRC Portal
Log into the VRC Portal, and submit your log file.
Only the most recent zip file for each qualification task will be kept.
It is a good idea to download the file that was just uploaded and replay the contained log data. This will verify that the upload was successful.
Step 9: Upload the videos to the VRC Portal
Create a single file vrc_video_q{n}.zip , where n is the number of the Qualification task (1, 2, 3 or 4). The zip file should contain the operator and screen videos following the naming convention described in the Video Guide.
Example:
zip vrc_video_q1.zip 2013_04_30_13_31_C001_OCS_Walk_1.mp4 2013_04_30_13_31_C001_OP_Walk_1.mts
Go to the VRC 2013 Videos tab of your VRC Portal team's page, and upload your video.
Only the most recent zip video for each qualification task will be kept.