Skip to content

Commit

Permalink
Use quoted includes for lcm and external lcmtypes
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Feb 23, 2018
1 parent 9e4f477 commit b46d64d
Show file tree
Hide file tree
Showing 12 changed files with 13 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <string>

#include <gflags/gflags.h>
#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/find_resource.h"
#include "drake/examples/kuka_iiwa_arm/iiwa_common.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
#include <list>
#include <memory>

#include <lcm/lcm-cpp.hpp>
#include "bot_core/robot_state_t.hpp"
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
Expand Down
2 changes: 1 addition & 1 deletion examples/kuka_iiwa_arm/kuka_plan_runner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#include <iostream>
#include <memory>

#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"
#include "robotlocomotion/robot_plan_t.hpp"

#include "drake/common/drake_assert.h"
Expand Down
2 changes: 1 addition & 1 deletion examples/kuka_iiwa_arm/move_iiwa_ee.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
/// during, and after the commanded motion.

#include <gflags/gflags.h>
#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"
#include "robotlocomotion/robot_plan_t.hpp"

#include "drake/common/drake_assert.h"
Expand Down
2 changes: 1 addition & 1 deletion lcm/lcm_receive_thread.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <atomic>
#include <thread>

#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_copyable.h"

Expand Down
2 changes: 1 addition & 1 deletion multibody/rigid_body_plant/viewer_draw_translator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <cstdint>
#include <vector>

#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_assert.h"
#include "drake/systems/framework/basic_vector.h"
Expand Down
2 changes: 1 addition & 1 deletion perception/estimators/dev/test/test_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include <vector>

#include <Eigen/Dense>
#include <bot_core/pointcloud_t.hpp>
#include <gtest/gtest.h>
#include "bot_core/pointcloud_t.hpp"

#include "drake/common/drake_assert.h"
#include "drake/lcm/drake_lcm.h"
Expand Down
2 changes: 1 addition & 1 deletion systems/controllers/InstantaneousQPController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <utility>
#include <vector>

#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_assert.h"
#include "drake/common/eigen_types.h"
Expand Down
6 changes: 2 additions & 4 deletions systems/estimators/dev/pose_estimation_test.cc
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#include <random>
#include <stdexcept>

#include <lcm/lcm-cpp.hpp>
// TODO(russt): Figure out why do I need the lcmtypes here. Inconsistent with
// https://github.com/mwoehlke-kitware/bot_core_lcmtypes/pull/1#issuecomment-269343143
#include <lcmtypes/bot_core/pointcloud_t.hpp>
#include "bot_core/pointcloud_t.hpp"
#include "lcm/lcm-cpp.hpp"

#include "drake/common/eigen_types.h"
#include "drake/common/find_resource.h"
Expand Down
2 changes: 1 addition & 1 deletion systems/lcm/lcmt_drake_signal_translator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <cstdint>
#include <vector>

#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_assert.h"
#include "drake/lcmt_drake_signal.hpp"
Expand Down
2 changes: 1 addition & 1 deletion systems/lcm/test/lcm_driven_loop_test.cc
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "drake/systems/lcm/lcm_driven_loop.h"

#include <gtest/gtest.h>
#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/lcm/drake_lcm.h"
Expand Down
2 changes: 1 addition & 1 deletion systems/robotInterfaces/QPLocomotionPlan.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

#include <Eigen/Core>
#include <Eigen/Geometry>
#include <lcm/lcm-cpp.hpp>
#include "lcm/lcm-cpp.hpp"

#include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h"
#include "drake/common/trajectories/piecewise_polynomial.h"
Expand Down

0 comments on commit b46d64d

Please sign in to comment.