Skip to content
This repository has been archived by the owner on Jul 23, 2024. It is now read-only.

Commit

Permalink
Fix cpplint errors (ros#497)
Browse files Browse the repository at this point in the history
* Fix include order for cpplint

Relates to ament/ament_lint#324

Signed-off-by: Jacob Perron <[email protected]>

* Replace C-style cast with static_cast

Signed-off-by: Jacob Perron <[email protected]>
  • Loading branch information
jacobperron authored Jan 12, 2022
1 parent 9e94db4 commit 401f6e5
Show file tree
Hide file tree
Showing 36 changed files with 285 additions and 278 deletions.
14 changes: 7 additions & 7 deletions tf2_bullet/include/tf2_bullet/tf2_bullet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,15 @@
#ifndef TF2_BULLET__TF2_BULLET_HPP_
#define TF2_BULLET__TF2_BULLET_HPP_

#include <tf2/convert.h>
#include <LinearMath/btQuaternion.h>
#include <LinearMath/btScalar.h>
#include <LinearMath/btTransform.h>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <tf2_ros/buffer_interface.h>

#include <iostream>

#include "tf2/convert.h"
#include "LinearMath/btQuaternion.h"
#include "LinearMath/btScalar.h"
#include "LinearMath/btTransform.h"
#include "geometry_msgs/msg/point_stamped.hpp"
#include "tf2_ros/buffer_interface.h"

#if (BT_BULLET_VERSION <= 282)
// Suppress compilation warning on older versions of Bullet.
// TODO(mjcarroll): Remove this when all platforms have the fix upstream.
Expand Down
10 changes: 4 additions & 6 deletions tf2_bullet/test/test_tf2_bullet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,10 @@

/** \author Wim Meeussen */


#include <tf2_bullet/tf2_bullet.hpp>
#include <rclcpp/rclcpp.hpp>
#include <gtest/gtest.h>
#include <tf2/convert.h>

#include "tf2_bullet/tf2_bullet.hpp"
#include "rclcpp/rclcpp.hpp"
#include "gtest/gtest.h"
#include "tf2/convert.h"

TEST(TfBullet, ConvertVector)
{
Expand Down
19 changes: 10 additions & 9 deletions tf2_eigen/include/tf2_eigen/tf2_eigen.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,18 @@
#ifndef TF2_EIGEN__TF2_EIGEN_HPP_
#define TF2_EIGEN__TF2_EIGEN_HPP_

#include <tf2/convert.h>
#include <tf2_ros/buffer_interface.h>
#include <Eigen/Geometry>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/quaternion_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
#include <tf2_ros/buffer.h>

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/point_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/quaternion_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"

#include "tf2/convert.h"
#include "tf2_ros/buffer.h"
#include "tf2_ros/buffer_interface.h"

namespace tf2
{
Expand Down
32 changes: 17 additions & 15 deletions tf2_eigen/test/tf2_eigen-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,24 +34,26 @@
#endif
#endif

#include <gtest/gtest.h>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rclcpp/clock.hpp>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <Eigen/Geometry>

#include <cmath>
#include <memory>

#include <Eigen/Geometry> // NOLINT

#include "gtest/gtest.h"

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/point_stamped.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp/clock.hpp"

#include "tf2/convert.h"
#include "tf2/transform_datatypes.h"
#include "tf2_eigen/tf2_eigen.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"

TEST(TfEigen, ConvertVector3dStamped)
{
const tf2::Stamped<Eigen::Vector3d> v(Eigen::Vector3d(1, 2, 3), tf2::TimePoint(
Expand Down
4 changes: 2 additions & 2 deletions tf2_eigen_kdl/include/tf2_eigen_kdl/tf2_eigen_kdl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@
#include <Eigen/Core>
#include <Eigen/Geometry>

#include <kdl/frames.hpp>
#include "kdl/frames.hpp"

#include <tf2/impl/convert.h>
#include "tf2/impl/convert.h"

#include "tf2_eigen_kdl/visibility_control.h"

Expand Down
41 changes: 21 additions & 20 deletions tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,29 +32,30 @@
#ifndef TF2_GEOMETRY_MSGS__TF2_GEOMETRY_MSGS_HPP_
#define TF2_GEOMETRY_MSGS__TF2_GEOMETRY_MSGS_HPP_

#include <tf2/convert.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2_ros/buffer_interface.h>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/quaternion_stamped.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <geometry_msgs/msg/vector3_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/pose_with_covariance.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <geometry_msgs/msg/wrench.hpp>
#include <geometry_msgs/msg/wrench_stamped.hpp>
#include <kdl/frames.hpp>

#include <array>
#include <string>

#include "geometry_msgs/msg/point_stamped.hpp"
#include "geometry_msgs/msg/quaternion_stamped.hpp"
#include "geometry_msgs/msg/transform.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/vector3.hpp"
#include "geometry_msgs/msg/vector3_stamped.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_with_covariance.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/wrench.hpp"
#include "geometry_msgs/msg/wrench_stamped.hpp"
#include "kdl/frames.hpp"

#include "tf2/convert.h"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Transform.h"
#include "tf2/LinearMath/Vector3.h"
#include "tf2_ros/buffer_interface.h"

namespace tf2
{

Expand Down
14 changes: 7 additions & 7 deletions tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,17 +35,17 @@
#endif
#endif

#include <rclcpp/clock.hpp>
#include <tf2_ros/transform_listener.h>
#include <gtest/gtest.h>
#include <tf2_ros/buffer.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

// To get M_PI, especially on Windows.
#include <cmath>
#include <memory>
#include <string>

#include "gtest/gtest.h"

#include "rclcpp/clock.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"

std::unique_ptr<tf2_ros::Buffer> tf_buffer = nullptr;
static const double EPS = 1e-3;

Expand Down
12 changes: 6 additions & 6 deletions tf2_ros/include/tf2_ros/async_buffer_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,16 +30,16 @@
#ifndef TF2_ROS__ASYNC_BUFFER_INTERFACE_H_
#define TF2_ROS__ASYNC_BUFFER_INTERFACE_H_

#include <tf2_ros/visibility_control.h>
#include <tf2/time.h>
#include <tf2/transform_datatypes.h>

#include <geometry_msgs/msg/transform_stamped.hpp>

#include <functional>
#include <future>
#include <string>

#include "tf2_ros/visibility_control.h"
#include "tf2/time.h"
#include "tf2/transform_datatypes.h"

#include "geometry_msgs/msg/transform_stamped.hpp"

namespace tf2_ros
{

Expand Down
22 changes: 11 additions & 11 deletions tf2_ros/include/tf2_ros/buffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,23 +32,23 @@
#ifndef TF2_ROS__BUFFER_H_
#define TF2_ROS__BUFFER_H_

#include <tf2_ros/async_buffer_interface.h>
#include <tf2_ros/buffer_interface.h>
#include <tf2_ros/create_timer_interface.h>
#include <tf2_ros/visibility_control.h>
#include <tf2/buffer_core.h>
#include <tf2/time.h>

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2_msgs/srv/frame_graph.hpp>
#include <rclcpp/rclcpp.hpp>

#include <future>
#include <memory>
#include <mutex>
#include <string>
#include <unordered_map>

#include "tf2_ros/async_buffer_interface.h"
#include "tf2_ros/buffer_interface.h"
#include "tf2_ros/create_timer_interface.h"
#include "tf2_ros/visibility_control.h"
#include "tf2/buffer_core.h"
#include "tf2/time.h"

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2_msgs/srv/frame_graph.hpp"
#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
{

Expand Down
16 changes: 8 additions & 8 deletions tf2_ros/include/tf2_ros/buffer_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,17 +38,17 @@
#ifndef TF2_ROS__BUFFER_CLIENT_H_
#define TF2_ROS__BUFFER_CLIENT_H_

#include <tf2_ros/buffer_interface.h>
#include <tf2_ros/visibility_control.h>
#include <tf2/time.h>

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <tf2_msgs/action/lookup_transform.hpp>

#include <stdexcept>
#include <string>

#include "tf2_ros/buffer_interface.h"
#include "tf2_ros/visibility_control.h"
#include "tf2/time.h"

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "tf2_msgs/action/lookup_transform.hpp"

namespace tf2_ros
{
/**
Expand Down
20 changes: 10 additions & 10 deletions tf2_ros/include/tf2_ros/buffer_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,21 +32,21 @@
#ifndef TF2_ROS__BUFFER_INTERFACE_H_
#define TF2_ROS__BUFFER_INTERFACE_H_

#include <tf2_ros/visibility_control.h>
#include <tf2/transform_datatypes.h>
#include <tf2/exceptions.h>
#include <tf2/convert.h>

#include <builtin_interfaces/msg/duration.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rclcpp/rclcpp.hpp>

#include <chrono>
#include <functional>
#include <future>
#include <string>

#include "tf2_ros/visibility_control.h"
#include "tf2/transform_datatypes.h"
#include "tf2/exceptions.h"
#include "tf2/convert.h"

#include "builtin_interfaces/msg/duration.hpp"
#include "builtin_interfaces/msg/time.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
{
using TransformStampedFuture = std::shared_future<geometry_msgs::msg::TransformStamped>;
Expand Down
20 changes: 10 additions & 10 deletions tf2_ros/include/tf2_ros/buffer_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,22 +38,22 @@
#ifndef TF2_ROS__BUFFER_SERVER_H_
#define TF2_ROS__BUFFER_SERVER_H_

#include <tf2/time.h>
#include <tf2/buffer_core_interface.h>
#include <tf2_ros/visibility_control.h>

#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rclcpp/create_timer.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <tf2_msgs/action/lookup_transform.hpp>

#include <functional>
#include <list>
#include <memory>
#include <mutex>
#include <string>

#include "tf2/time.h"
#include "tf2/buffer_core_interface.h"
#include "tf2_ros/visibility_control.h"

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp/create_timer.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "tf2_msgs/action/lookup_transform.hpp"

namespace tf2_ros
{
/** \brief Action server for the action-based implementation of tf2::BufferCoreInterface.
Expand Down
11 changes: 5 additions & 6 deletions tf2_ros/include/tf2_ros/create_timer_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,17 +30,16 @@
#ifndef TF2_ROS__CREATE_TIMER_INTERFACE_H_
#define TF2_ROS__CREATE_TIMER_INTERFACE_H_

#include <tf2/time.h>

#include <tf2_ros/visibility_control.h>

#include <rclcpp/rclcpp.hpp>

#include <functional>
#include <memory>
#include <stdexcept>
#include <string>

#include "tf2/time.h"

#include "tf2_ros/visibility_control.h"

#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
{
Expand Down
12 changes: 6 additions & 6 deletions tf2_ros/include/tf2_ros/create_timer_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,15 @@
#ifndef TF2_ROS__CREATE_TIMER_ROS_H_
#define TF2_ROS__CREATE_TIMER_ROS_H_

#include <tf2_ros/create_timer_interface.h>
#include <tf2_ros/visibility_control.h>
#include <tf2/time.h>

#include <rclcpp/rclcpp.hpp>

#include <mutex>
#include <unordered_map>

#include "tf2_ros/create_timer_interface.h"
#include "tf2_ros/visibility_control.h"
#include "tf2/time.h"

#include "rclcpp/rclcpp.hpp"

namespace tf2_ros
{

Expand Down
Loading

0 comments on commit 401f6e5

Please sign in to comment.