Skip to content

Commit

Permalink
move publisher to depthai_bridge
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam committed Jul 4, 2023
1 parent cee8ae6 commit 2ad686f
Show file tree
Hide file tree
Showing 8 changed files with 18 additions and 10 deletions.
3 changes: 3 additions & 0 deletions depthai_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ find_package(sensor_msgs REQUIRED)
find_package(stereo_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(vision_msgs REQUIRED)
find_package(tf2_ros REQUIRED)

set(dependencies
camera_info_manager
Expand All @@ -48,6 +49,7 @@ set(dependencies
stereo_msgs
std_msgs
vision_msgs
tf2_ros
)

include_directories(
Expand All @@ -62,6 +64,7 @@ file(GLOB LIB_SRC
"src/ImgDetectionConverter.cpp"
"src/SpatialDetectionConverter.cpp"
"src/ImuConverter.cpp"
"src/TFPublisher.cpp"
)

add_library(${PROJECT_NAME} SHARED ${LIB_SRC})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,15 @@
#include "tf2_ros/static_transform_broadcaster.h"
#include "depthai/device/CalibrationHandler.hpp"
#include "rclcpp/node.hpp"
namespace depthai_ros_driver{

namespace dai {

namespace ros {
class TFPublisher{
public:
explicit TFPublisher(rclcpp::Node *node, dai::CalibrationHandler handler);
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tfPub;

};
}
}
1 change: 1 addition & 0 deletions depthai_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
<depend>std_msgs</depend>
<depend>stereo_msgs</depend>
<depend>vision_msgs</depend>
<depend>tf2_ros</depend>

<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>xacro</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "depthai_ros_driver/tf_publisher.hpp"
#include "depthai_bridge/TFPublisher.hpp"

#include "geometry_msgs/msg/quaternion.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
Expand All @@ -8,7 +8,8 @@
#include "tf2/LinearMath/Quaternion.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace depthai_ros_driver {
namespace dai {
namespace ros {
TFPublisher::TFPublisher(rclcpp::Node* node, dai::CalibrationHandler handler) {
tfPub = std::make_shared<tf2_ros::StaticTransformBroadcaster>(node);
auto json = handler.eepromToJson();
Expand Down Expand Up @@ -66,4 +67,5 @@ TFPublisher::TFPublisher(rclcpp::Node* node, dai::CalibrationHandler handler) {
tfPub->sendTransform(optical_ts);
}
}
} // namespace depthai_ros_driver
} // namespace ros
} // namespace dai
2 changes: 0 additions & 2 deletions depthai_ros_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ rclcpp_components
std_srvs
pluginlib
bondcpp
tf2_ros
)


Expand Down Expand Up @@ -106,7 +105,6 @@ target_link_libraries(
add_library(
${PROJECT_NAME} SHARED
src/camera.cpp
src/tf_publisher.cpp
src/pipeline/pipeline_generator.cpp
src/pipeline/base_types.cpp
)
Expand Down
3 changes: 2 additions & 1 deletion depthai_ros_driver/include/depthai_ros_driver/camera.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include "rclcpp/node.hpp"
#include "std_srvs/srv/trigger.hpp"
#include "bondcpp/bond.hpp"
#include "depthai_ros_driver/tf_publisher.hpp"
#include "depthai_bridge/TFPublisher.hpp"

namespace dai {
class Pipeline;
Expand Down Expand Up @@ -49,5 +49,6 @@ class Camera : public rclcpp::Node {
std::vector<std::unique_ptr<dai_nodes::BaseNode>> daiNodes;
bool camRunning = false;
std::unique_ptr<bond::Bond> bond;
std::unique_ptr<dai::ros::TFPublisher> tfPub;
};
} // namespace depthai_ros_driver
1 change: 0 additions & 1 deletion depthai_ros_driver/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
<depend>depthai_examples</depend>
<depend>pluginlib</depend>
<depend>bondcpp</depend>
<depend>tf2_ros</depend>
<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
4 changes: 2 additions & 2 deletions depthai_ros_driver/src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "depthai/device/Device.hpp"
#include "depthai/pipeline/Pipeline.hpp"
#include "depthai_ros_driver/pipeline/pipeline_generator.hpp"
#include "depthai_ros_driver/tf_publisher.hpp"
#include "depthai_bridge/TFPublisher.hpp"

namespace depthai_ros_driver {

Expand All @@ -31,7 +31,7 @@ void Camera::onConfigure() {
// std::unique_ptr<bond::Bond> bond = std::make_unique<bond::Bond>(this->get_name() + std::string("_bond"), this->get_name(), this->shared_from_this());
// bond->start();
// }
auto tf = std::make_shared<TFPublisher>(this, device->readCalibration());
tfPub = std::make_unique<dai::ros::TFPublisher>(this, device->readCalibration());
RCLCPP_INFO(this->get_logger(), "Camera ready!");
}

Expand Down

0 comments on commit 2ad686f

Please sign in to comment.