Skip to content

Commit

Permalink
Updating lint files, readme, and API
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <[email protected]>
  • Loading branch information
aaronchongth committed Apr 4, 2022
1 parent 0fa0b40 commit 7f33cc5
Show file tree
Hide file tree
Showing 13 changed files with 151 additions and 55 deletions.
2 changes: 1 addition & 1 deletion drake_ros_core/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ To build it:
1. [Download Drake binary](https://drake.mit.edu/from_binary.html), nightly or any stable releases after 14 Jan 2022.
1. Extract the Drake binary installation, install it's prerequisites, and [use this Python virutalenv trick](https://drake.mit.edu/from_binary.html).
1. Activate the drake virtual environment.
1. Build it using Colcon, or using CMake directly.
1. Build it using Colcon.

**Colcon**
1. Make a workspace `mkdir -p ./ws/src`
Expand Down
45 changes: 45 additions & 0 deletions drake_ros_examples/.clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
# -*- yaml -*-

# Taken from RobotLocomotion/drake @ 73925c7eb71361e2e97601af4182ba54072d192a
# This file determines clang-format's style settings; for details, refer to
# http://clang.llvm.org/docs/ClangFormatStyleOptions.html

BasedOnStyle: Google

Language: Cpp

# Force pointers to the type for C++.
DerivePointerAlignment: false
PointerAlignment: Left

# Specify the #include statement order. This implements the order mandated by
# the Google C++ Style Guide: related header, C headers, C++ headers, library
# headers, and finally the project headers.
#
# To obtain updated lists of system headers used in the below expressions, see:
# http://stackoverflow.com/questions/2027991/list-of-standard-header-files-in-c-and-c/2029106#2029106.
IncludeCategories:
# Spacers used by drake/tools/formatter.py.
- Regex: '^<clang-format-priority-15>$'
Priority: 15
- Regex: '^<clang-format-priority-25>$'
Priority: 25
- Regex: '^<clang-format-priority-35>$'
Priority: 35
- Regex: '^<clang-format-priority-45>$'
Priority: 45
# C system headers.
- Regex: '^[<"](aio|arpa/inet|assert|complex|cpio|ctype|curses|dirent|dlfcn|errno|fcntl|fenv|float|fmtmsg|fnmatch|ftw|glob|grp|iconv|inttypes|iso646|langinfo|libgen|limits|locale|math|monetary|mqueue|ndbm|netdb|net/if|netinet/in|netinet/tcp|nl_types|poll|pthread|pwd|regex|sched|search|semaphore|setjmp|signal|spawn|stdalign|stdarg|stdatomic|stdbool|stddef|stdint|stdio|stdlib|stdnoreturn|string|strings|stropts|sys/ipc|syslog|sys/mman|sys/msg|sys/resource|sys/select|sys/sem|sys/shm|sys/socket|sys/stat|sys/statvfs|sys/time|sys/times|sys/types|sys/uio|sys/un|sys/utsname|sys/wait|tar|term|termios|tgmath|threads|time|trace|uchar|ulimit|uncntrl|unistd|utime|utmpx|wchar|wctype|wordexp)\.h[">]$'
Priority: 20
# C++ system headers (as of C++17).
- Regex: '^[<"](algorithm|any|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|charconv|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|execution|filesystem|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|memory_resource|mutex|new|numeric|optional|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|string_view|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|variant|vector)[">]$'
Priority: 30
# Other libraries' h files (with angles).
- Regex: '^<'
Priority: 40
# Your project's h files.
- Regex: '^"drake_ros_examples'
Priority: 50
# Other libraries' h files (with quotes).
- Regex: '^"'
Priority: 40
7 changes: 5 additions & 2 deletions drake_ros_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,11 @@ find_package(drake_ros_viz REQUIRED)
add_subdirectory(examples)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_clang_format REQUIRED)
find_package(ament_cmake_cpplint REQUIRED)

ament_clang_format(CONFIG_FILE .clang-format)
ament_cpplint()
endif()

ament_package()
64 changes: 64 additions & 0 deletions drake_ros_examples/CPPLINT.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
# Taken from RobotLocomotion/drake @ 73925c7eb71361e2e97601af4182ba54072d192a
#
# Copyright 2016 Robot Locomotion Group @ CSAIL. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without modification,
# are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice,
# this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
# 3. Neither the name of the copyright holder nor the names of its contributors
# may be used to endorse or promote products derived from this software without
# specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
# EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
# OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
# SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
# OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
# HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

# Stop searching for additional config files.
set noparent

# Disable a warning about C++ features that were not in the original
# C++11 specification (and so might not be well-supported). In the
# case of Drake, our supported minimum platforms are new enough that
# this warning is irrelevant.
filter=-build/c++11

# Drake uses `#pragma once`, not the `#ifndef FOO_H` guard.
# https://drake.mit.edu/styleguide/cppguide.html#The__pragma_once_Guard
filter=-build/header_guard
filter=+build/pragma_once

# Disable cpplint's include order. We have our own via //tools:drakelint.
filter=-build/include_order

# TODO(hidmic): uncomment when ament_cpplint updates its vendored cpplint
# version to support the following filters. Also remove corresponding NOLINT
# codetags in sources.
## Allow private, sibling include files.
#filter=-build/include_subdir

# We do not care about the whitespace details of a TODO comment. It is not
# relevant for easy grepping, and the GSG does not specify any particular
# whitespace style. (We *do* care what the "TODO(username)" itself looks like
# because GSG forces a particular style there, but that formatting is covered
# by the readability/todo rule, which we leave enabled.)
filter=-whitespace/todo

# TODO(#1805) Fix this.
filter=-legal/copyright

# Ignore code that isn't ours.
exclude_files=third_party

# It's not worth lint-gardening the documentation.
exclude_files=doc
39 changes: 7 additions & 32 deletions drake_ros_examples/README.md
Original file line number Diff line number Diff line change
@@ -1,38 +1,28 @@
# Drake ROS Examples

This is a collection of examples built around `drake_ros_systems` C++ and Python APIs.
This is a collection of examples built around `drake_ros` libraries' C++ and Python APIs.

## Building

This package has been built and tested on Ubuntu Focal with ROS Rolling, using a Drake nightly from April 2021.
This package has been built and tested on Ubuntu Focal with ROS Rolling, using a Drake nightly or any stable releases after 14 Jan 2022.
It may work on other versions of ROS and Drake, but it hasn't been tested.

To build it:

1. [Install ROS Rolling](https://index.ros.org/doc/ros2/Installation/Rolling/)
1. Source your ROS installation `. /opt/ros/rolling/setup.bash`
1. [Download April-ish 2021 Drake binary](https://drake.mit.edu/from_binary.html)
1. Extract the Drake binary installation, install it's prerequisites, and [use this Python virutalenv trick](https://drake.mit.edu/python_bindings.html#inside-virtualenv).
1. Activate the drake virtual environment
1. Build it using Colcon, or using CMake directly
1. [Download Drake binary](https://drake.mit.edu/from_binary.html), nightly or any stable releases after 14 Jan 2022.
1. Extract the Drake binary installation, install it's prerequisites, and [use this Python virutalenv trick](https://drake.mit.edu/from_binary.html).
1. Activate the drake virtual environment.
1. Build it using Colcon.

**Colcon**
1. Make a workspace `mkdir -p ./ws/src`
1. `cd ./ws/src`
1. Get this code `git clone https://github.com/RobotLocomotion/drake-ros.git`
1. `cd ..`
1. Build this package and its dependencies `colcon build --packages-up-to drake_ros_systems`
1. Build this package `colcon build --packages-up-to drake_ros_examples`

**CMake**
1. Get this code `git clone https://github.com/RobotLocomotion/drake-ros.git`
1. Build the [`drake_ros_systems`](../drake_ros_systems/README.md#building) package using CMake first.
1. Manually set `CMAKE_PREFIX_PATH`: `export CMAKE_PREFIX_PATH=$CMAKE_PREFIX_PATH:$(pwd)/drake-ros/drake_ros_systems/install`
1. `cd drake-ros/drake_ros_examples`
1. Make a build and install folder to avoid installing to the whole system `mkdir build install`
1. `cd build`
1. Configure the project `cmake -DCMAKE_INSTALL_PREFIX=$(pwd)/../install ..`
1. Build the project `make && make install`

## Running

* If you built with `colcon`, then source your workspace.
Expand All @@ -44,21 +34,6 @@ To build it:

Now you can run C++ and Python examples using `ros2 run drake_ros_examples <example-executable-or-script>`.


* If you built with plain CMake, then source the ROS workspace and set these variables.

```
. /opt/ros/rolling/setup.bash
# Also make sure to activate drake virtual environment
# CD to repository root
export LD_LIBRARY_PATH=$(pwd)/drake_ros_systems/install/lib:$LD_LIBRARY_PATH
export LD_LIBRARY_PATH=$(pwd)/drake_ros_examples/install/lib:$LD_LIBRARY_PATH
export PYTHONPATH=$(pwd)/drake_ros_systems/install/lib/$(python -c 'import sys; print(f"python{sys.version_info[0]}.{sys.version_info[1]}")')/site-packages:$PYTHONPATH
export PYTHONPATH=$(pwd)/drake_ros_examples/install/lib/$(python -c 'import sys; print(f"python{sys.version_info[0]}.{sys.version_info[1]}")')/site-packages:$PYTHONPATH
```

Now you can run C++ and Python examples from the install folder using `./drake-ros/drake_ros_examples/install/lib/drake_ros_examples/<example-executable-or-script>`.

## List of examples

- [RS flip flop](./examples/rs_flip_flop): a latch with a ROS 2 topic interface.
Expand Down
2 changes: 0 additions & 2 deletions drake_ros_examples/examples/iiwa_manipulator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,5 +17,3 @@ Run RViz in a different terminal with your ROS installation sourced to visualize
```
ros2 run rviz2 rviz2 -d iiwa_manipulator.rviz
```


Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021https://www.youtube.com/watch?v=SUQnduNzsw8 Open Source Robotics Foundation, Inc.
// Copyright 2021 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -22,9 +22,9 @@

#include <drake/examples/manipulation_station/manipulation_station.h>

#include <drake_ros_core/drake_ros.hpp>
#include <drake_ros_core/ros_interface_system.hpp>
#include <drake_ros_viz/rviz_visualizer.hpp>
#include <drake_ros_core/drake_ros.h>
#include <drake_ros_core/ros_interface_system.h>
#include <drake_ros_viz/rviz_visualizer.h>

#include <cmath>
#include <memory>
Expand All @@ -45,8 +45,9 @@ int main()
{
drake::systems::DiagramBuilder<double> builder;

auto ros_interface_system =
builder.AddSystem<RosInterfaceSystem>(std::make_unique<DrakeRos>());
drake_ros_core::init();
auto ros_interface_system = builder.AddSystem<RosInterfaceSystem>(
std::make_unique<DrakeRos>("iiwa_manipulator_node"));

auto manipulation_station = builder.AddSystem<ManipulationStation>();
manipulation_station->SetupClutterClearingStation();
Expand Down
10 changes: 6 additions & 4 deletions drake_ros_examples/examples/iiwa_manipulator/iiwa_manipulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,9 @@

import numpy as np

from drake_ros_systems import RosInterfaceSystem
from drake_ros_systems import RvizVisualizer
import drake_ros_core
from drake_ros_core import RosInterfaceSystem
from drake_ros_viz import RvizVisualizer

from pydrake.examples.manipulation_station import ManipulationStation
from pydrake.systems.analysis import Simulator
Expand All @@ -25,15 +26,16 @@
from pydrake.systems.primitives import ConstantVectorSource
from pydrake.systems.primitives import Sine


def main():
builder = DiagramBuilder()

ros_interface_system = builder.AddSystem(RosInterfaceSystem())
drake_ros_core.init()
ros_interface_system = builder.AddSystem(RosInterfaceSystem("iiwa_manipulator_node"))

manipulation_station = builder.AddSystem(ManipulationStation())
manipulation_station.SetupClutterClearingStation()
manipulation_station.Finalize()
pdb.set_trace()

# Make the base joint swing sinusoidally.
constant_term = builder.AddSystem(ConstantVectorSource(
Expand Down
12 changes: 7 additions & 5 deletions drake_ros_examples/examples/rs_flip_flop/rs_flip_flop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@
#include <drake/systems/framework/diagram_builder.h>
#include <drake/systems/framework/leaf_system.h>

#include <drake_ros_core/drake_ros.hpp>
#include <drake_ros_core/ros_interface_system.hpp>
#include <drake_ros_core/ros_publisher_system.hpp>
#include <drake_ros_core/ros_subscriber_system.hpp>
#include <drake_ros_core/drake_ros.h>
#include <drake_ros_core/ros_interface_system.h>
#include <drake_ros_core/ros_publisher_system.h>
#include <drake_ros_core/ros_subscriber_system.h>

#include <std_msgs/msg/bool.hpp>

Expand Down Expand Up @@ -109,7 +109,9 @@ int main()

rclcpp::QoS qos{10};

auto sys_ros_interface = builder.AddSystem<RosInterfaceSystem>(std::make_unique<DrakeRos>());
drake_ros_core::init();
auto sys_ros_interface = builder.AddSystem<RosInterfaceSystem>(
std::make_unique<DrakeRos>("rs_flip_flop_node"));
auto sys_pub_Q = builder.AddSystem(
RosPublisherSystem::Make<std_msgs::msg::Bool>(
"Q", qos, sys_ros_interface->get_ros_interface()));
Expand Down
4 changes: 3 additions & 1 deletion drake_ros_examples/examples/rs_flip_flop/rs_flip_flop.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import drake_ros_core
from drake_ros_core import RosInterfaceSystem
from drake_ros_core import RosPublisherSystem
from drake_ros_core import RosSubscriberSystem
Expand Down Expand Up @@ -83,7 +84,8 @@ def main():
# S: true R: true | Q: invalid Q_not: invalid
builder = DiagramBuilder()

sys_ros_interface = builder.AddSystem(RosInterfaceSystem())
drake_ros_core.init()
sys_ros_interface = builder.AddSystem(RosInterfaceSystem("rs_flip_flop_node"))

qos = QoSProfile(depth=10)

Expand Down
4 changes: 4 additions & 0 deletions drake_ros_examples/pycodestyle.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[pycodestyle]
# This is close to the ignore's that Drake uses, as of
# https://github.com/RobotLocomotion/drake/blob/v0.35.0/tools/lint/python_lint.bzl#L7
ignore = 'E121,E123,E126,E226,E24,E704,W503'
2 changes: 1 addition & 1 deletion drake_ros_tf2/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ To build it:
1. [Download Drake binary](https://drake.mit.edu/from_binary.html), nightly or any stable releases after 14 Jan 2022.
1. Extract the Drake binary installation, install it's prerequisites, and [use this Python virutalenv trick](https://drake.mit.edu/from_binary.html).
1. Activate the Drake virtual environment.
1. Build it using Colcon, or using CMake directly.
1. Build it using Colcon.

**Colcon**
1. Make a workspace `mkdir -p ./ws/src`
Expand Down
2 changes: 1 addition & 1 deletion drake_ros_viz/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ To build it:
1. [Download Drake binary](https://drake.mit.edu/from_binary.html), nightly or any stable releases after 14 Jan 2022.
1. Extract the Drake binary installation, install it's prerequisites, and [use this Python virutalenv trick](https://drake.mit.edu/from_binary.html).
1. Activate the drake virtual environment.
1. Build it using Colcon, or using CMake directly.
1. Build it using Colcon.

**Colcon**
1. Make a workspace `mkdir -p ./ws/src`
Expand Down

0 comments on commit 7f33cc5

Please sign in to comment.