Skip to content

Commit

Permalink
Run clang-format-includes
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Jun 16, 2017
1 parent 7022cd8 commit c6cf65f
Show file tree
Hide file tree
Showing 14 changed files with 15 additions and 16 deletions.
5 changes: 2 additions & 3 deletions drake/automotive/maliput/rndf/test/spline_helpers_test.cc
Original file line number Diff line number Diff line change
@@ -1,16 +1,15 @@
#include "drake/automotive/maliput/rndf/spline_helpers.h"

#include <cmath>
#include <iostream>
#include <memory>
#include <tuple>
#include <vector>

#include <gtest/gtest.h>

#include "ignition/math/Spline.hh"
#include "ignition/math/Vector3.hh"

#include "drake/automotive/maliput/rndf/spline_helpers.h"

namespace drake {
namespace maliput {
namespace rndf {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <memory>

#include "bot_core/atlas_command_t.hpp"

#include "drake/common/drake_copyable.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/system/joint_level_controller_system.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
#include <utility>

#include "drake/common/drake_copyable.h"
#include "drake/manipulation/util/robot_state_msg_translator.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/humanoid_status.h"
#include "drake/manipulation/util/robot_state_msg_translator.h"
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/framework/leaf_system.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
#include "drake/examples/QPInverseDynamicsForHumanoids/system/humanoid_status_translator_system.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/system/joint_level_controller_system.h"
#include "drake/examples/QPInverseDynamicsForHumanoids/system/qp_controller_system.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/systems/framework/diagram_builder.h"

namespace drake {
namespace examples {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <vector>

#include <gflags/gflags.h>

#include "bot_core/robot_state_t.hpp"
#include "robotlocomotion/robot_plan_t.hpp"

Expand All @@ -17,8 +16,8 @@
#include "drake/lcmtypes/drake/lcmt_schunk_wsg_command.hpp"
#include "drake/manipulation/schunk_wsg/schunk_wsg_lcm.h"
#include "drake/math/rotation_matrix.h"
#include "drake/multibody/rigid_body_plant/drake_visualizer.h"
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/multibody/rigid_body_plant/drake_visualizer.h"
#include "drake/multibody/rigid_body_plant/rigid_body_plant.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/framework/diagram.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include "drake/common/eigen_types.h"
#include "drake/examples/kuka_iiwa_arm/pick_and_place/action.h"
#include "drake/examples/kuka_iiwa_arm/pick_and_place/world_state.h"
#include "drake/manipulation/planner/constraint_relaxing_ik.h"
#include "drake/lcmt_schunk_wsg_command.hpp"
#include "drake/manipulation/planner/constraint_relaxing_ik.h"

namespace drake {
namespace examples {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include "drake/examples/kuka_iiwa_arm/pick_and_place/pick_and_place_state_machine.h"

#include <gtest/gtest.h>

#include "bot_core/robot_state_t.hpp"
#include "robotlocomotion/robot_plan_t.hpp"

Expand Down
2 changes: 1 addition & 1 deletion drake/manipulation/schunk_wsg/schunk_wsg_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include <memory>

#include "drake/common/trajectories/trajectory.h"
#include "drake/manipulation/schunk_wsg/gen/schunk_wsg_trajectory_generator_state_vector.h"
#include "drake/lcmt_schunk_wsg_status.hpp"
#include "drake/manipulation/schunk_wsg/gen/schunk_wsg_trajectory_generator_state_vector.h"
#include "drake/systems/framework/leaf_system.h"

namespace drake {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "drake/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.h"

#include <cmath>

#include <gtest/gtest.h>

#include "drake/common/eigen_types.h"
Expand Down
1 change: 1 addition & 0 deletions drake/solvers/decision_variable.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <list>

#include <Eigen/Core>

#include "drake/common/symbolic_variable.h"
Expand Down
5 changes: 2 additions & 3 deletions drake/systems/analysis/test/simulator_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,20 @@
#include <map>

#include <gtest/gtest.h>

#include <unsupported/Eigen/AutoDiff>

#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/text_logging.h"
#include "drake/common/test/is_dynamic_castable.h"
#include "drake/common/text_logging.h"
#include "drake/systems/analysis/explicit_euler_integrator.h"
#include "drake/systems/analysis/implicit_euler_integrator.h"
#include "drake/systems/analysis/runge_kutta2_integrator.h"
#include "drake/systems/analysis/runge_kutta3_integrator.h"
#include "drake/systems/analysis/test/controlled_spring_mass_system/controlled_spring_mass_system.h"
#include "drake/systems/analysis/test/stateless_system.h"
#include "drake/systems/analysis/test/logistic_system.h"
#include "drake/systems/analysis/test/my_spring_mass_system.h"
#include "drake/systems/analysis/test/stateless_system.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/plants/spring_mass_system/spring_mass_system.h"

Expand Down
2 changes: 1 addition & 1 deletion drake/systems/controllers/inverse_dynamics_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@

#include "drake/common/drake_copyable.h"
#include "drake/multibody/rigid_body_tree.h"
#include "drake/systems/controllers/state_feedback_controller_interface.h"
#include "drake/systems/controllers/pid_controller.h"
#include "drake/systems/controllers/state_feedback_controller_interface.h"
#include "drake/systems/framework/diagram.h"

namespace drake {
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/framework/input_port_evaluator_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@
#include <sstream>

#include "drake/common/drake_copyable.h"
#include "drake/systems/framework/output_port_value.h"
#include "drake/systems/framework/input_port_descriptor.h"
#include "drake/systems/framework/output_port_value.h"

namespace drake {
namespace systems {
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/framework/test/diagram_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

#include "drake/common/eigen_types.h"
#include "drake/common/test/is_dynamic_castable.h"
#include "drake/systems/analysis/test/stateless_system.h"
#include "drake/systems/framework/basic_vector.h"
#include "drake/systems/framework/diagram_builder.h"
#include "drake/systems/framework/leaf_system.h"
Expand All @@ -15,7 +16,6 @@
#include "drake/systems/primitives/gain.h"
#include "drake/systems/primitives/integrator.h"
#include "drake/systems/primitives/zero_order_hold.h"
#include "drake/systems/analysis/test/stateless_system.h"

namespace drake {
namespace systems {
Expand Down

0 comments on commit c6cf65f

Please sign in to comment.