Skip to content

Commit

Permalink
fix: include order
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
  • Loading branch information
wep21 committed May 3, 2022
1 parent 9954bb9 commit 90a43f5
Show file tree
Hide file tree
Showing 79 changed files with 548 additions and 474 deletions.
12 changes: 6 additions & 6 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.hpp
Expand Up @@ -15,16 +15,16 @@
#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_CAMERA_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_CAMERA_HPP_

#include <gazebo/plugins/CameraPlugin.hh>
#include <gazebo/plugins/DepthCameraPlugin.hh>
#include <gazebo_plugins/multi_camera_plugin.hpp>
#include <gazebo_ros/node.hpp>
#include <std_msgs/msg/empty.hpp>

#include <memory>
#include <string>
#include <vector>

#include "gazebo/plugins/CameraPlugin.hh"
#include "gazebo/plugins/DepthCameraPlugin.hh"
#include <gazebo_plugins/multi_camera_plugin.hpp>
#include <gazebo_ros/node.hpp>
#include <std_msgs/msg/empty.hpp>

namespace gazebo_plugins
{
class GazeboRosCameraPrivate;
Expand Down
6 changes: 3 additions & 3 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.hpp
Expand Up @@ -15,11 +15,11 @@
#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_ELEVATOR_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_ELEVATOR_HPP_

#include <gazebo/plugins/ElevatorPlugin.hh>
#include <std_msgs/msg/string.hpp>

#include <memory>

#include "gazebo/plugins/ElevatorPlugin.hh"
#include <std_msgs/msg/string.hpp>

namespace gazebo_plugins
{
class GazeboRosElevatorPrivate;
Expand Down
6 changes: 3 additions & 3 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.hpp
Expand Up @@ -15,11 +15,11 @@
#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_FORCE_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_FORCE_HPP_

#include <gazebo/common/Plugin.hh>
#include <geometry_msgs/msg/wrench.hpp>

#include <memory>

#include "gazebo/common/Plugin.hh"
#include <geometry_msgs/msg/wrench.hpp>

namespace gazebo_plugins
{
class GazeboRosForcePrivate;
Expand Down
6 changes: 3 additions & 3 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.hpp
Expand Up @@ -15,11 +15,11 @@
#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_HARNESS_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_HARNESS_HPP_

#include <gazebo/plugins/HarnessPlugin.hh>
#include <std_msgs/msg/empty.hpp>

#include <memory>

#include "gazebo/plugins/HarnessPlugin.hh"
#include <std_msgs/msg/empty.hpp>

namespace gazebo_plugins
{
class GazeboRosHarnessPrivate;
Expand Down
Expand Up @@ -16,12 +16,12 @@
#ifndef GAZEBO_PLUGINS__GAZEBO_ROS_IMU_SENSOR_HPP_
#define GAZEBO_PLUGINS__GAZEBO_ROS_IMU_SENSOR_HPP_

#include <gazebo/plugins/ImuSensorPlugin.hh>
#include <sensor_msgs/msg/imu.hpp>

#include <string>
#include <memory>

#include "gazebo/plugins/ImuSensorPlugin.hh"
#include <sensor_msgs/msg/imu.hpp>

namespace gazebo_plugins
{

Expand Down
36 changes: 19 additions & 17 deletions gazebo_plugins/src/gazebo_ros_ackermann_drive.cpp
Expand Up @@ -12,32 +12,34 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gazebo/common/Time.hh>
#include <gazebo/common/PID.hh>
#include <gazebo/physics/Joint.hh>
#include <gazebo/physics/Link.hh>
#include <gazebo/physics/Model.hh>
#include <gazebo/physics/World.hh>
#include <gazebo/physics/physics.hh>
#include <memory>
#include <string>
#include <vector>

#include "gazebo/common/Time.hh"
#include "gazebo/common/PID.hh"
#include "gazebo/physics/Joint.hh"
#include "gazebo/physics/Link.hh"
#include "gazebo/physics/Model.hh"
#include "gazebo/physics/World.hh"
#include "gazebo/physics/physics.hh"
#ifdef IGN_PROFILER_ENABLE
#include "ignition/common/Profiler.hh"
#endif
#include "sdf/sdf.hh"

#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_listener.h"

#include <gazebo_plugins/gazebo_ros_ackermann_drive.hpp>
#include <gazebo_ros/conversions/builtin_interfaces.hpp>
#include <gazebo_ros/conversions/geometry_msgs.hpp>
#include <gazebo_ros/node.hpp>
#include <geometry_msgs/msg/twist.hpp>
#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#endif
#include <nav_msgs/msg/odometry.hpp>
#include <std_msgs/msg/float32.hpp>
#include <sdf/sdf.hh>

#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <string>
#include <vector>

namespace gazebo_plugins
{
Expand Down
26 changes: 13 additions & 13 deletions gazebo_plugins/src/gazebo_ros_camera.cpp
Expand Up @@ -12,14 +12,21 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <sdf/Element.hh>
#include <gazebo/common/Events.hh>
#include <gazebo/rendering/Distortion.hh>
#include <gazebo/sensors/SensorTypes.hh>
#include <algorithm>
#include <limits>
#include <memory>
#include <mutex>
#include <string>
#include <vector>

#include "gazebo/common/Events.hh"
#include "gazebo/rendering/Distortion.hh"
#include "gazebo/sensors/SensorTypes.hh"
#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#include "ignition/common/Profiler.hh"
#endif
#include <ignition/math/Helpers.hh>
#include "ignition/math/Helpers.hh"
#include "sdf/Element.hh"

#include <camera_info_manager/camera_info_manager.hpp>
#include <gazebo_plugins/gazebo_ros_camera.hpp>
Expand All @@ -33,13 +40,6 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <algorithm>
#include <limits>
#include <memory>
#include <mutex>
#include <string>
#include <vector>

#define FLOAT_SIZE sizeof(float)

namespace gazebo_plugins
Expand Down
33 changes: 17 additions & 16 deletions gazebo_plugins/src/gazebo_ros_diff_drive.cpp
Expand Up @@ -50,36 +50,37 @@
* \date 22th of May 2014
*/

#include <gazebo/common/Time.hh>
#include <gazebo/physics/Joint.hh>
#include <gazebo/physics/Link.hh>
#include <gazebo/physics/Model.hh>
#include <gazebo/physics/World.hh>
#include <memory>
#include <string>
#include <vector>

#include "gazebo/common/Time.hh"
#include "gazebo/physics/Joint.hh"
#include "gazebo/physics/Link.hh"
#include "gazebo/physics/Model.hh"
#include "gazebo/physics/World.hh"
#ifdef IGN_PROFILER_ENABLE
#include "ignition/common/Profiler.hh"
#endif
#include "sdf/sdf.hh"

#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_listener.h"

#include <gazebo_plugins/gazebo_ros_diff_drive.hpp>
#include <gazebo_ros/conversions/builtin_interfaces.hpp>
#include <gazebo_ros/conversions/geometry_msgs.hpp>
#include <gazebo_ros/node.hpp>
#include <geometry_msgs/msg/pose2_d.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sdf/sdf.hh>

#ifdef NO_ERROR
// NO_ERROR is a macro defined in Windows that's used as an enum in tf2
#undef NO_ERROR
#endif

#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#endif

#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <string>
#include <vector>

namespace gazebo_plugins
{
Expand Down
6 changes: 3 additions & 3 deletions gazebo_plugins/src/gazebo_ros_elevator.cpp
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <limits>
#include <memory>

#include <gazebo_plugins/gazebo_ros_elevator.hpp>
#include <gazebo_ros/node.hpp>
#include <std_msgs/msg/string.hpp>

#include <limits>
#include <memory>

namespace gazebo_plugins
{
class GazeboRosElevatorPrivate
Expand Down
20 changes: 11 additions & 9 deletions gazebo_plugins/src/gazebo_ros_force.cpp
Expand Up @@ -12,20 +12,22 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gazebo/common/Events.hh>
#include <gazebo/physics/Link.hh>
#include <gazebo/physics/Model.hh>
#include <memory>
#include <string>

#include "gazebo/common/Events.hh"
#include "gazebo/physics/Link.hh"
#include "gazebo/physics/Model.hh"
#ifdef IGN_PROFILER_ENABLE
#include "ignition/common/Profiler.hh"
#endif

#include <gazebo_plugins/gazebo_ros_force.hpp>
#include <gazebo_ros/conversions/geometry_msgs.hpp>
#include <gazebo_ros/node.hpp>
#include <geometry_msgs/msg/wrench.hpp>
#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#endif
#include <rclcpp/rclcpp.hpp>

#include <memory>
#include <string>
#include <rclcpp/rclcpp.hpp>

namespace gazebo_plugins
{
Expand Down
15 changes: 8 additions & 7 deletions gazebo_plugins/src/gazebo_ros_gps_sensor.cpp
Expand Up @@ -12,21 +12,22 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <iostream>
#include <memory>
#include <string>

#ifdef IGN_PROFILER_ENABLE
#include "ignition/common/Profiler.hh"
#endif

#include <builtin_interfaces/msg/time.hpp>
#include <gazebo_plugins/gazebo_ros_gps_sensor.hpp>
#include <gazebo_ros/conversions/builtin_interfaces.hpp>
#include <gazebo_ros/conversions/geometry_msgs.hpp>
#include <gazebo_ros/node.hpp>
#include <gazebo_ros/utils.hpp>
#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#endif
#include <sensor_msgs/msg/nav_sat_fix.hpp>

#include <iostream>
#include <memory>
#include <string>
#include <sensor_msgs/msg/nav_sat_fix.hpp>

namespace gazebo_plugins
{
Expand Down
29 changes: 15 additions & 14 deletions gazebo_plugins/src/gazebo_ros_hand_of_god.cpp
Expand Up @@ -40,24 +40,25 @@
*
*/

#include <gazebo/physics/Link.hh>
#include <gazebo/physics/Model.hh>
#include <gazebo_plugins/gazebo_ros_hand_of_god.hpp>
#include <gazebo_ros/conversions/geometry_msgs.hpp>
#include <gazebo_ros/conversions/builtin_interfaces.hpp>
#include <gazebo_ros/node.hpp>
#include <memory>
#include <string>

#include "gazebo/physics/Link.hh"
#include "gazebo/physics/Model.hh"
#include "gazebo_plugins/gazebo_ros_hand_of_god.hpp"
#include "gazebo_ros/conversions/geometry_msgs.hpp"
#include "gazebo_ros/conversions/builtin_interfaces.hpp"
#include "gazebo_ros/node.hpp"
#ifdef IGN_PROFILER_ENABLE
#include <ignition/common/Profiler.hh>
#include "ignition/common/Profiler.hh"
#endif
#include <sdf/sdf.hh>
#include "sdf/sdf.hh"

#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"

#include <memory>
#include <string>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

namespace gazebo_plugins
{
Expand Down
13 changes: 7 additions & 6 deletions gazebo_plugins/src/gazebo_ros_harness.cpp
Expand Up @@ -12,15 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gazebo/physics/Model.hh>
#include <gazebo_plugins/gazebo_ros_harness.hpp>
#include <gazebo_ros/node.hpp>
#include <sdf/sdf.hh>
#include <std_msgs/msg/float32.hpp>

#include <memory>
#include <string>

#include "gazebo/physics/Model.hh"
#include "gazebo_plugins/gazebo_ros_harness.hpp"
#include "gazebo_ros/node.hpp"
#include "sdf/sdf.hh"

#include <std_msgs/msg/float32.hpp>

namespace gazebo_plugins
{
class GazeboRosHarnessPrivate
Expand Down

0 comments on commit 90a43f5

Please sign in to comment.