Skip to content

Commit

Permalink
.h->.hppに対応
Browse files Browse the repository at this point in the history
  • Loading branch information
mizonon committed Oct 7, 2024
1 parent 53c770c commit a6a63d7
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion crane_x7_examples/src/aruco_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include "sensor_msgs/msg/image.hpp"
#include "opencv2/opencv.hpp"
#include "opencv2/aruco.hpp"
#include "cv_bridge/cv_bridge.h"
#include "cv_bridge/cv_bridge.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Matrix3x3.h"
#include "tf2_ros/transform_broadcaster.h"
Expand Down
4 changes: 2 additions & 2 deletions crane_x7_examples/src/color_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@
#include "tf2_ros/transform_broadcaster.h"
#include "opencv2/opencv.hpp"
#include "opencv2/imgproc/imgproc.hpp"
#include "cv_bridge/cv_bridge.h"
#include "image_geometry/pinhole_camera_model.h"
#include "cv_bridge/cv_bridge.hpp"
#include "image_geometry/pinhole_camera_model.hpp"
using std::placeholders::_1;

class ImageSubscriber : public rclcpp::Node
Expand Down

0 comments on commit a6a63d7

Please sign in to comment.