Skip to content

Commit 6bb401d

Browse files
committed
Style fixes for newer cpplint.
Signed-off-by: Chris Lalancette <[email protected]>
1 parent 4468435 commit 6bb401d

File tree

5 files changed

+21
-22
lines changed

5 files changed

+21
-22
lines changed

joy/include/joy/joy.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -32,15 +32,15 @@
3232

3333
#include <SDL.h>
3434

35-
#include <rclcpp/rclcpp.hpp>
36-
#include <sensor_msgs/msg/joy.hpp>
37-
#include <sensor_msgs/msg/joy_feedback.hpp>
38-
3935
#include <future>
4036
#include <memory>
4137
#include <string>
4238
#include <thread>
4339

40+
#include <rclcpp/rclcpp.hpp>
41+
#include <sensor_msgs/msg/joy.hpp>
42+
#include <sensor_msgs/msg/joy_feedback.hpp>
43+
4444
namespace joy
4545
{
4646

joy/src/joy.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -27,13 +27,6 @@
2727
* POSSIBILITY OF SUCH DAMAGE.
2828
*/
2929

30-
#include <SDL.h>
31-
32-
#include <rclcpp/rclcpp.hpp>
33-
#include <rclcpp_components/register_node_macro.hpp>
34-
#include <sensor_msgs/msg/joy.hpp>
35-
#include <sensor_msgs/msg/joy_feedback.hpp>
36-
3730
#include <algorithm>
3831
#include <chrono>
3932
#include <functional>
@@ -43,6 +36,13 @@
4336
#include <string>
4437
#include <thread>
4538

39+
#include <SDL.h>
40+
41+
#include <rclcpp/rclcpp.hpp>
42+
#include <rclcpp_components/register_node_macro.hpp>
43+
#include <sensor_msgs/msg/joy.hpp>
44+
#include <sensor_msgs/msg/joy_feedback.hpp>
45+
4646
#include "joy/joy.hpp"
4747

4848
namespace joy

joy_linux/src/joy_linux_node.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -38,17 +38,17 @@
3838
#include <sys/stat.h>
3939
#include <unistd.h>
4040

41-
#include <diagnostic_updater/diagnostic_updater.hpp>
42-
#include <rclcpp/rclcpp.hpp>
43-
#include <sensor_msgs/msg/joy.hpp>
44-
#include <sensor_msgs/msg/joy_feedback_array.hpp>
45-
4641
#include <chrono>
4742
#include <functional>
4843
#include <future>
4944
#include <memory>
5045
#include <string>
5146

47+
#include <diagnostic_updater/diagnostic_updater.hpp>
48+
#include <rclcpp/rclcpp.hpp>
49+
#include <sensor_msgs/msg/joy.hpp>
50+
#include <sensor_msgs/msg/joy_feedback_array.hpp>
51+
5252
/// \brief Opens, reads from and publishes joystick events
5353
class Joystick
5454
{

spacenav/src/spacenav.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,15 +33,15 @@
3333

3434
#include "spacenav/spacenav.hpp"
3535

36-
#include <rclcpp/rclcpp.hpp>
37-
#include <rclcpp_components/register_node_macro.hpp>
38-
3936
#include <chrono>
4037
#include <functional>
4138
#include <memory>
4239
#include <utility>
4340
#include <vector>
4441

42+
#include <rclcpp/rclcpp.hpp>
43+
#include <rclcpp_components/register_node_macro.hpp>
44+
4545
#include "spnav.h" // NOLINT
4646

4747
#define SPACENAV_FULL_SCALE_PARAM_S "full_scale"

wiimote/include/wiimote/wiimote_controller.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,11 +51,10 @@
5151
#include <std_srvs/srv/empty.hpp>
5252
#include <wiimote_msgs/msg/state.hpp>
5353

54-
// We need to link against these
55-
#include <bluetooth/bluetooth.h> // libbluetooth.so
54+
#include "bluetooth/bluetooth.h"
5655
namespace wiimote_c
5756
{
58-
#include <cwiid.h> // libcwiid.so
57+
#include "cwiid.h" // NOLINT, cpplint wants us to have a directory
5958
}
6059

6160
#include "wiimote/stat_vector_3d.hpp"

0 commit comments

Comments
 (0)