Create a URDF/SDF robot
To create a Multibody robot, read from a robot description file is a convenient way. Drake support parsing URDF and SDF files.
Run the demo
Create workspace & get model
cd drake
mkdir -p examples/double_pendulum_pid/models
curl -o examples/double_pendulum_pid/models/double_pendulum.sdf https://raw.githubusercontent.com/guzhaoyuan/drake/tutorial/examples/double_pendulum_pid/models/double_pendulum.sdfCreate the source file
load(
"@drake//tools/skylark:drake_cc.bzl",
"drake_cc_binary",
)
load("//tools/install:install_data.bzl", "install_data")
drake_cc_binary(
name = "run_double_pendulum_passive_exe",
srcs = [
"run_double_pendulum_passive.cc",
],
data = [
":models",
"//tools:drake_visualizer",
],
deps = [
"//common:find_resource",
"//common:text_logging_gflags",
"//geometry:geometry_visualization",
"//lcm",
"//multibody/parsing",
"//multibody/plant",
"//systems/analysis",
"//systems/framework",
"@sdformat",
],
)
install_data()Run the code
Drake is deprecating the drake_visualizer. The alternative is meldis. If you don't have drake_visualizer, run the following in the first window instead:
The Code Explained
The install_data() copy the items under the data tag to the build folder so when the program actually runs, it will be able to access the data files.
DRAKE_DEMAND is an assertion that ensures that the FLAGS_simulation_time is larger than zero. If not fulfilled, the program will stop throwing an exception. We could always use DRAKE_DEMAND to verify data correctness.
Create a DiagramBuilder that helps to add system blocks and connect different systems.
Add a SceneGraph<double> to the diagram using builder. Note that system have we added was recorded and stored. The diagram and all the system are created when we call:
Create a MultibodyPlant<double> that represents the double pendulum. Then we set its name and connect it to SceneGraph so we could see the model later in simulation.
Here we create a parser that actually create the model. It will parse the provided URDF or SDF file line by line, and call Drake functions internally to create a multibody in tree structure.
We then create a fixed joint WeldJoint between the robot base and the world frame. So the robot base always stay fixed on the ground. Once the MultibodyPlant is finished, we call dp->Finalize() so we seal the plant, making sure the robot model is not mutable during simulation. The DRAKE_DEMAND makes sure that the MultibodyPlant is created successfully.
After the plant is created. We use builder again to connect the MultibodyPlant system with other blocks in the diagram. scene_graph receive the MultibodyPlant current state and compute the collision in the system. It then reports all the collision infomation to the MultibodyPlant so MultibodyPlant will decide the contact force according to the contact body material.
Create the diagram and diagram_context. Get the plant_context by getting subsystem context from the diagram_context.
Set the initial position of the robot away from the home position.
Create a Simulator , set the simulation parameter. Then actually do the simulation by advance to the desired time.
Quick access to the result
Add code to you repository.
Run.
Extensions
Similar example of parsing an Allegro hand.
Last updated
Was this helpful?