I am trying to build and simulate a simple diff-drive robot under drake to get familiar with the components offered. I created a simple URDF which bases on existing PR2 URDF. I load the model with AddMultibodyPlantSceneGraph
. With following snippet,
std::string vox_nav_drake_ros_package_path =
ament_index_cpp::get_package_share_directory("vox_nav_drake_ros");
drake::systems::DiagramBuilder<double> builder;
auto [plant, scene_graph] =
drake::multibody::AddMultibodyPlantSceneGraph(&builder, 0.1 /* time_step */);
const std::string & pathname = vox_nav_drake_ros_package_path + "/urdf/botanbot.urdf";
drake::multibody::Parser parser(&plant);
parser.AddModelFromFile(pathname);
plant.Finalize();
auto context = plant.CreateDefaultContext();
auto zero_torque =
builder.AddSystem<drake::systems::ConstantVectorSource<double>>(
Eigen::VectorXd::Zero(3));
builder.Connect(
zero_torque->get_output_port(),
plant.get_actuation_input_port());
auto diagram = builder.Build();
drake::systems::Simulator<double> simulator(plant);
simulator.Initialize();
while (1) {
simulator.AdvanceTo(simulator.get_context().get_time() + 0.1);
}
The error says that I need to connect the Actuation input port for model instance, which I already do, but the error persists and I don't understand why.
Here is the URDF I use;
<?xml version="1.0"?>
<robot name="botanbot">
<!-- BEGIN LINKS -->
<!-- BEGIN LINKS RELATED TO ROBOT BODY-->
<link name="base_link">
<visual>
<origin xyz="-0.019375 0.005287 0.340756" rpy="0 0 0" />
<geometry>
<mesh filename="/home/atas/colcon_ws/install/vox_nav_drake_ros/share/vox_nav_drake_ros/meshes/base_simplified.obj" />
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0" />
</material>
</visual>
<inertial>
<mass value="1326.0" />
<inertia ixx="2581.13354740" ixy="0" ixz="0" iyy="591.30846112" iyz="0" izz="2681.9500862" />
</inertial>
</link>
<!-- END JOINTS RELATED TO ROBOT BODY -->
<!--//////////////////////////////////-->
<!-- END JOINTS -->
<link name="base_footprint">
<inertial>
<mass value="1.0" />
<origin xyz="0 0 0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size="0.01 0.01 0.01" />
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0" />
</material>
</visual>
</link>
<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.051" />
<child link="base_link" />
<parent link="base_footprint" />
</joint>
<link name="base_link_0" />
<link name="base_link_1" />
<!-- RigidBodyTree only supports fixed or unactuated joints to the
world. Prismatic joints with a transmission don't work
correctly. -->
<link name="base_link_for_rbt_compat" />
<joint name="world_joint_for_rbt_compat" type="fixed">
<parent link="world" />
<child link="base_link_for_rbt_compat" />
</joint>
<joint name="x" type="prismatic">
<parent link="base_link_for_rbt_compat" />
<child link="base_link_0" />
<axis xyz="1 0 0" />
</joint>
<joint name="y" type="prismatic">
<parent link="base_link_0" />
<child link="base_link_1" />
<axis xyz="0 1 0" />
</joint>
<joint name="theta" type="revolute">
<parent link="base_link_1" />
<child link="base_footprint" />
<axis xyz="0 0 1" />
<limit effort="100" lower="-3.14" upper="3.14" velocity="100" />
</joint>
<transmission name="x_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="x">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="x_motor">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="y_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="y">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="y_motor">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="theta_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="theta">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="thata_motor">
<hardwareInterface>PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>