forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Adds realsense-ros dependency for URDF and meshes (RobotLocomotion#14203
) This commit provides Drake the ability to fetch the realsense-ros upstream repository during build: IntelRealSense/realsense-ros: - It gives Drake access to the realsense d415 xacro and mesh files - After the download, xacro files are modified to cleanly stitch into a URDF in a Drake environment (rather than their native ROS environment) - A test is provided that is closely based (copied + slightly modified) on the YCB meshes simple parsing tests
- Loading branch information
1 parent
2144375
commit b0b7513
Showing
8 changed files
with
196 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,46 @@ | ||
# -*- python -*- | ||
|
||
load("@drake//tools/lint:lint.bzl", "add_lint_tests") | ||
load("@drake//tools/install:install_data.bzl", "install_data") | ||
load( | ||
"@drake//tools/skylark:drake_cc.bzl", | ||
"drake_cc_googletest", | ||
) | ||
load("@drake//tools/workspace:forward_files.bzl", "forward_files") | ||
load( | ||
"@drake//tools/workspace/intel_realsense_ros:files.bzl", | ||
"realsense2_description_files", | ||
) | ||
|
||
# This package is public so that other packages can refer to | ||
# individual files in models from their bazel rules. | ||
package( | ||
default_visibility = ["//visibility:public"], | ||
) | ||
|
||
_REALSENSE2_DESCRIPTION_FILES = forward_files( | ||
srcs = ["@intel_realsense_ros//:" + | ||
x for x in realsense2_description_files()], | ||
dest_prefix = "", | ||
strip_prefix = "@intel_realsense_ros//:realsense2_description/", | ||
visibility = ["//visibility:private"], | ||
) | ||
|
||
install_data( | ||
extra_prod_models = _REALSENSE2_DESCRIPTION_FILES, | ||
) | ||
|
||
drake_cc_googletest( | ||
name = "realsense_parse_test", | ||
data = [":models"], | ||
deps = [ | ||
"//common:find_resource", | ||
"//geometry:geometry_visualization", | ||
"//geometry:scene_graph", | ||
"//multibody/parsing", | ||
"//systems/analysis:simulator", | ||
"//systems/framework:diagram_builder", | ||
], | ||
) | ||
|
||
add_lint_tests() |
82 changes: 82 additions & 0 deletions
82
manipulation/models/realsense2_description/test/realsense_parse_test.cc
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,82 @@ | ||
/* | ||
@file | ||
Parses and visualizes Realsense d415. | ||
If you wish to visualize this mesh, in its own terminal run: | ||
$ bazel-bin/tools/drake_visualizer | ||
In a new terminal, run example of showing a Realsense d415: | ||
$ bazel run \ | ||
//manipulation/models/realsense2_description:realsense_parse_test -- \ | ||
--visualize=true | ||
*/ | ||
|
||
#include <string> | ||
|
||
#include <fmt/format.h> | ||
#include <gflags/gflags.h> | ||
#include <gtest/gtest.h> | ||
|
||
#include "drake/common/find_resource.h" | ||
#include "drake/geometry/geometry_visualization.h" | ||
#include "drake/geometry/scene_graph.h" | ||
#include "drake/multibody/parsing/parser.h" | ||
#include "drake/systems/analysis/simulator.h" | ||
#include "drake/systems/framework/diagram_builder.h" | ||
|
||
DEFINE_bool( | ||
visualize, false, "Publish model to Drake Visualizer."); | ||
|
||
namespace drake { | ||
namespace manipulation { | ||
namespace { | ||
|
||
using geometry::ConnectDrakeVisualizer; | ||
using geometry::SceneGraph; | ||
using multibody::AddMultibodyPlantSceneGraph; | ||
using multibody::Parser; | ||
using systems::DiagramBuilder; | ||
using systems::Simulator; | ||
|
||
class ParseTest : public testing::TestWithParam<std::string> {}; | ||
|
||
TEST_P(ParseTest, ParsesUrdfAndVisualizes) { | ||
const std::string object_name = GetParam(); | ||
const std::string filename = FindResourceOrThrow(fmt::format( | ||
"drake/manipulation/models/realsense2_description/urdf/{}.urdf", | ||
object_name)); | ||
|
||
DiagramBuilder<double> builder; | ||
auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, 0.0); | ||
// Record the default number of models before a new model is added. | ||
const int default_num_models = plant.num_model_instances(); | ||
|
||
// Check to ensure URDF is parsable. | ||
EXPECT_NO_THROW(Parser(&plant).AddModelFromFile(filename)); | ||
|
||
// Ensure there was exactly one model instance added for the new model. | ||
EXPECT_EQ(plant.num_model_instances() - default_num_models, 1); | ||
|
||
// Visualize via publishing, if requested. | ||
if (FLAGS_visualize) { | ||
ConnectDrakeVisualizer(&builder, scene_graph); | ||
plant.Finalize(); | ||
auto diagram = builder.Build(); | ||
drake::log()->info("Visualize: {}", object_name); | ||
Simulator<double> simulator(*diagram); | ||
simulator.Initialize(); | ||
diagram->Publish(simulator.get_context()); | ||
} | ||
} | ||
|
||
// Note: We use a test suite here, even if currently for only one value, to | ||
// allow for easily adding more models under test in the future without | ||
// rewriting the test code. | ||
INSTANTIATE_TEST_SUITE_P(RealsenseD415, ParseTest, testing::Values("d415")); | ||
|
||
} // namespace | ||
} // namespace manipulation | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,5 @@ | ||
# -*- python -*- | ||
|
||
load("//tools/lint:lint.bzl", "add_lint_tests") | ||
|
||
add_lint_tests() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,12 @@ | ||
# -*- python -*- | ||
|
||
# List files to be exported from the upstream | ||
# IntelRealsense/realsense-ros repository | ||
|
||
def realsense2_description_files(): | ||
return [ | ||
"realsense2_description/LICENSE", | ||
"realsense2_description/meshes/d415.stl", | ||
"realsense2_description/package.xml", | ||
"realsense2_description/urdf/d415.urdf", | ||
] |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,23 @@ | ||
# -*- python -*- | ||
|
||
load("@drake//tools/workspace/ros_xacro:defs.bzl", "xacro_file") | ||
|
||
licenses(["notice"]) # Apache-2.0 | ||
|
||
package(default_visibility = ["//visibility:public"]) | ||
|
||
xacro_file( | ||
name = "realsense2_description/urdf/d415.urdf", | ||
src = "realsense2_description/urdf/test_d415_camera.urdf.xacro", | ||
data = [ | ||
"realsense2_description/urdf/_d415.urdf.xacro", | ||
"realsense2_description/urdf/_materials.urdf.xacro", | ||
"realsense2_description/urdf/_usb_plug.urdf.xacro", | ||
], | ||
) | ||
|
||
exports_files( | ||
srcs = glob([ | ||
"realsense2_description/**", | ||
], allow_empty = False), | ||
) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,24 @@ | ||
# -*- python -*- | ||
|
||
load("@drake//tools/workspace:github.bzl", "github_archive") | ||
|
||
def intel_realsense_ros_repository( | ||
name, | ||
mirrors = None): | ||
github_archive( | ||
name = name, | ||
repository = "IntelRealSense/realsense-ros", | ||
# N.B. Even though 2.2.x series is not the highest-numbered release, we | ||
# are using it here because it aligns with the ROS Melodic version | ||
# released for Ubuntu 18.04. | ||
commit = "2.2.17", | ||
sha256 = "babffbd3b2d20c94431436fc50606fddf8712dd7e9392d9da3fd228b432f9cfe", # noqa | ||
build_file = "@drake//tools/workspace/intel_realsense_ros:package.BUILD.bazel", # noqa | ||
patch_cmds = [ | ||
"cp LICENSE realsense2_description/", | ||
"sed -i.orig -e 's|$(find realsense2_description)/urdf/||' realsense2_description/urdf/*.xacro", # noqa | ||
"sed -i -e 's|$(arg use_nominal_extrinsics)|false|' realsense2_description/urdf/*.xacro", # noqa | ||
"sed -i -e 's|$(arg add_plug)|false|' realsense2_description/urdf/*.xacro", # noqa | ||
], | ||
mirrors = mirrors, | ||
) |