From 06fae597e1a37f208f5456ed7819dd9e8af35197 Mon Sep 17 00:00:00 2001
From: Florian Vahl <7vahl@informatik.uni-hamburg.de>
Date: Tue, 19 Mar 2024 13:23:06 +0100
Subject: [PATCH 01/21] Use ipm distortion instead of image rectification
---
.../bitbots_basler_camera/launch/basler_camera.launch | 7 +------
bitbots_misc/bitbots_ipm/config/soccer_ipm.yaml | 1 +
bitbots_misc/bitbots_ipm/launch/ipm.launch | 10 ++++++----
3 files changed, 8 insertions(+), 10 deletions(-)
diff --git a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
index fc9a6a203..f52e9a44a 100644
--- a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
+++ b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
@@ -23,14 +23,9 @@
-
+
-
-
-
-
-
diff --git a/bitbots_misc/bitbots_ipm/config/soccer_ipm.yaml b/bitbots_misc/bitbots_ipm/config/soccer_ipm.yaml
index cdcdc4f72..15f4637e7 100644
--- a/bitbots_misc/bitbots_ipm/config/soccer_ipm.yaml
+++ b/bitbots_misc/bitbots_ipm/config/soccer_ipm.yaml
@@ -25,3 +25,4 @@ soccer_ipm:
z: 1.0
output_frame: 'base_footprint'
+ use_distortion: true
diff --git a/bitbots_misc/bitbots_ipm/launch/ipm.launch b/bitbots_misc/bitbots_ipm/launch/ipm.launch
index 520c03a24..a080e5361 100644
--- a/bitbots_misc/bitbots_ipm/launch/ipm.launch
+++ b/bitbots_misc/bitbots_ipm/launch/ipm.launch
@@ -9,9 +9,10 @@
-
-
+
+
+
@@ -25,9 +26,10 @@
-
-
+
+
+
From 79fcd4f29286f56554503794e2dded2ff13cca1c Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Tue, 19 Mar 2024 14:50:18 +0000
Subject: [PATCH 02/21] Add plotjuggler to dev container
---
.devcontainer/Dockerfile | 5 +----
1 file changed, 1 insertion(+), 4 deletions(-)
diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile
index aac4a5070..803934756 100644
--- a/.devcontainer/Dockerfile
+++ b/.devcontainer/Dockerfile
@@ -57,12 +57,9 @@ RUN apt-get install -y \
ros-iron-camera-calibration \
ros-iron-desktop \
ros-iron-joint-state-publisher-gui \
- # ros-iron-plotjuggler-ros containing plotjuggler ros plugins
- # build currently fails and is not available as a package so we
- # have to manually install plotjuggler and plotjuggler-msgs
- # https://github.com/PlotJuggler/plotjuggler-ros-plugins/issues/59
ros-iron-plotjuggler \
ros-iron-plotjuggler-msgs \
+ ros-iron-plotjuggler-ros \
ros-iron-rmw-cyclonedds-cpp \
ros-iron-rqt-robot-monitor \
ros-iron-soccer-vision-3d-rviz-markers
From 89b707d491a6c2239331bf29fcac4502d47f88bc Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Tue, 19 Mar 2024 14:51:09 +0000
Subject: [PATCH 03/21] Fix vision qos
---
bitbots_vision/bitbots_vision/vision.py | 10 +++++++++-
1 file changed, 9 insertions(+), 1 deletion(-)
diff --git a/bitbots_vision/bitbots_vision/vision.py b/bitbots_vision/bitbots_vision/vision.py
index 5f476d84e..86f9ca2a0 100755
--- a/bitbots_vision/bitbots_vision/vision.py
+++ b/bitbots_vision/bitbots_vision/vision.py
@@ -8,6 +8,7 @@
from cv_bridge import CvBridge
from rcl_interfaces.msg import SetParametersResult
from rclpy.node import Node
+from rclpy.qos import qos_profile_sensor_data
from sensor_msgs.msg import Image
from bitbots_vision.vision_modules import ros_utils, yoeo
@@ -125,7 +126,14 @@ def _set_up_vision_components(self, new_config: Dict) -> None:
def _register_subscribers(self, config: Dict) -> None:
self._sub_image = ros_utils.create_or_update_subscriber(
- self, self._config, config, self._sub_image, "ROS_img_msg_topic", Image, callback=self._image_callback
+ self,
+ self._config,
+ config,
+ self._sub_image,
+ "ROS_img_msg_topic",
+ Image,
+ callback=self._image_callback,
+ qos_profile=qos_profile_sensor_data,
)
def _image_callback(self, image_msg: Image) -> None:
From 6c79cb74fd8760e98ee5ab7225f44a75afbdd159 Mon Sep 17 00:00:00 2001
From: Florian Vahl <7vahl@informatik.uni-hamburg.de>
Date: Tue, 19 Mar 2024 19:20:50 +0100
Subject: [PATCH 04/21] Revert qos
---
bitbots_vision/bitbots_vision/vision.py | 2 --
1 file changed, 2 deletions(-)
diff --git a/bitbots_vision/bitbots_vision/vision.py b/bitbots_vision/bitbots_vision/vision.py
index 86f9ca2a0..03891d5e7 100755
--- a/bitbots_vision/bitbots_vision/vision.py
+++ b/bitbots_vision/bitbots_vision/vision.py
@@ -8,7 +8,6 @@
from cv_bridge import CvBridge
from rcl_interfaces.msg import SetParametersResult
from rclpy.node import Node
-from rclpy.qos import qos_profile_sensor_data
from sensor_msgs.msg import Image
from bitbots_vision.vision_modules import ros_utils, yoeo
@@ -133,7 +132,6 @@ def _register_subscribers(self, config: Dict) -> None:
"ROS_img_msg_topic",
Image,
callback=self._image_callback,
- qos_profile=qos_profile_sensor_data,
)
def _image_callback(self, image_msg: Image) -> None:
From bbcd3ebdaf2113b9e6d19412b13883c0505d9975 Mon Sep 17 00:00:00 2001
From: Florian Vahl <7vahl@informatik.uni-hamburg.de>
Date: Tue, 19 Mar 2024 19:21:00 +0100
Subject: [PATCH 05/21] Add custom postprocessing
---
.../bitbots_basler_camera/CMakeLists.txt | 26 +++++++-
.../src/postprocessing.cpp | 60 +++++++++++++++++++
2 files changed, 85 insertions(+), 1 deletion(-)
create mode 100644 bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
diff --git a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
index e94d25096..8fc154e4f 100644
--- a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
+++ b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
@@ -1,11 +1,35 @@
cmake_minimum_required(VERSION 3.5)
project(bitbots_basler_camera)
-find_package(bitbots_docs REQUIRED)
+# Add support for C++17
+if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 17)
+endif()
+
+find_package(rclcpp REQUIRED)
find_package(ament_cmake REQUIRED)
+find_package(bitbots_docs REQUIRED)
+find_package(backward_ros REQUIRED)
+find_package(OpenCV REQUIRED)
+
+add_compile_options(-Wall -Werror -Wno-unused)
+
+add_executable(postprocessing src/postprocessing.cpp)
+
+target_link_libraries(postprocessing
+ ${OpenCV_LIBRARIES}
+)
+
+ament_target_dependencies(
+ postprocessing
+ ament_cmake
+ bitbots_docs
+ rclcpp)
enable_bitbots_docs()
+install(TARGETS postprocessing DESTINATION lib/${PROJECT_NAME})
+
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
new file mode 100644
index 000000000..2870407cf
--- /dev/null
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -0,0 +1,60 @@
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+
+using std::placeholders::_1;
+
+namespace postprocessing {
+
+
+class PostProcessor {
+ std::shared_ptr node_;
+
+ // Declare subscriber
+ //rclcpp::Subscription::SharedPtr head_mode_subscriber_;
+ //rclcpp::Subscription::SharedPtr joint_state_subscriber_;
+
+ // Declare publisher
+ //rclcpp::Publisher::SharedPtr position_publisher_;
+
+ public:
+ PostProcessor() : node_(std::make_shared("post_processor")) {
+ // Initialize publisher for head motor goals
+ //position_publisher_ = node_->create_publisher("head_motor_goals", 10);
+
+ // Initialize subscriber for head mode
+ //head_mode_subscriber_ = node_->create_subscription(
+ // "head_mode", 10, [this](const bitbots_msgs::msg::HeadMode::SharedPtr msg) { head_mode_callback(msg); });
+
+ }
+
+ /**
+ * @brief Callback used to update the head mode
+ */
+ //void head_mode_callback(const bitbots_msgs::msg::HeadMode::SharedPtr msg) { head_mode_ = msg->head_mode; }
+
+ /**
+ * @brief A getter that returns the node
+ */
+ std::shared_ptr get_node() { return node_; }
+};
+} // namespace move_head
+
+int main(int argc, char* argv[]) {
+ rclcpp::init(argc, argv);
+ rclcpp::experimental::executors::EventsExecutor exec;
+ auto post_processor = std::make_shared();
+ exec.add_node(post_processor->get_node());
+ exec.spin();
+ rclcpp::shutdown();
+
+ return 0;
+}
From 31d216f6ac3f2b06ef0dc29842a0daa7f41ae079 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Tue, 19 Mar 2024 19:56:05 +0000
Subject: [PATCH 06/21] Use own image post processing node
---
.../bitbots_basler_camera/CMakeLists.txt | 17 ++--
.../bitbots_basler_camera/config/binning.yaml | 3 -
.../launch/basler_camera.launch | 23 ++---
.../bitbots_basler_camera/package.xml | 6 +-
.../src/postprocessing.cpp | 98 +++++++++++++++----
5 files changed, 103 insertions(+), 44 deletions(-)
delete mode 100644 bitbots_misc/bitbots_basler_camera/config/binning.yaml
diff --git a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
index 8fc154e4f..596badf8a 100644
--- a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
+++ b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
@@ -6,25 +6,30 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
-find_package(rclcpp REQUIRED)
find_package(ament_cmake REQUIRED)
-find_package(bitbots_docs REQUIRED)
find_package(backward_ros REQUIRED)
+find_package(bitbots_docs REQUIRED)
+find_package(cv_bridge REQUIRED)
+find_package(image_transport REQUIRED)
find_package(OpenCV REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(sensor_msgs REQUIRED)
add_compile_options(-Wall -Werror -Wno-unused)
add_executable(postprocessing src/postprocessing.cpp)
-target_link_libraries(postprocessing
- ${OpenCV_LIBRARIES}
-)
+target_link_libraries(postprocessing ${OpenCV_LIBRARIES})
ament_target_dependencies(
postprocessing
ament_cmake
bitbots_docs
- rclcpp)
+ cv_bridge
+ image_transport
+ rclcpp
+ sensor_msgs
+ OpenCV)
enable_bitbots_docs()
diff --git a/bitbots_misc/bitbots_basler_camera/config/binning.yaml b/bitbots_misc/bitbots_basler_camera/config/binning.yaml
deleted file mode 100644
index 7f43f9905..000000000
--- a/bitbots_misc/bitbots_basler_camera/config/binning.yaml
+++ /dev/null
@@ -1,3 +0,0 @@
-decimation_x: 4
-decimation_y: 4
-interpolation: 3
diff --git a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
index f52e9a44a..8c297b0d9 100644
--- a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
+++ b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
@@ -13,19 +13,12 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/bitbots_misc/bitbots_basler_camera/package.xml b/bitbots_misc/bitbots_basler_camera/package.xml
index b08289f66..7f249425b 100644
--- a/bitbots_misc/bitbots_basler_camera/package.xml
+++ b/bitbots_misc/bitbots_basler_camera/package.xml
@@ -13,8 +13,12 @@
Hamburg Bit-Botsbitbots_docs
+ cv_bridge
+ image_transport
+ libopencv-devpylon_ros2_camera_wrapper
- image_proc
+ rclcpp
+ sensor_msgsament_cmake
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
index 2870407cf..79200d2fc 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -1,52 +1,112 @@
#include
+#include
+#include
#include
#include
+#include
#include
#include
#include
#include
#include
-#include
-#include
-
-using std::placeholders::_1;
+using std::placeholders::_1, std::placeholders::_2;
namespace postprocessing {
-
class PostProcessor {
std::shared_ptr node_;
- // Declare subscriber
- //rclcpp::Subscription::SharedPtr head_mode_subscriber_;
- //rclcpp::Subscription::SharedPtr joint_state_subscriber_;
+ image_transport::TransportHints transport_hints_;
+ std::unique_ptr image_sub_;
+ std::unique_ptr image_pub_;
- // Declare publisher
- //rclcpp::Publisher::SharedPtr position_publisher_;
+ int binning_factor_x_ = 1;
+ int binning_factor_y_ = 1;
public:
- PostProcessor() : node_(std::make_shared("post_processor")) {
- // Initialize publisher for head motor goals
- //position_publisher_ = node_->create_publisher("head_motor_goals", 10);
-
- // Initialize subscriber for head mode
- //head_mode_subscriber_ = node_->create_subscription(
- // "head_mode", 10, [this](const bitbots_msgs::msg::HeadMode::SharedPtr msg) { head_mode_callback(msg); });
+ PostProcessor()
+ : node_(std::make_shared("post_processor")),
+ transport_hints_(node_.get()),
+ image_sub_(std::make_unique(image_transport::create_camera_subscription(
+ node_.get(), "in/image_raw", std::bind(&PostProcessor::image_callback, this, _1, _2),
+ transport_hints_.getTransport()))),
+ image_pub_(std::make_unique(
+ image_transport::create_camera_publisher(node_.get(), "out/image_proc"))) {
+ // Declare parameters
+ node_->declare_parameter("binning_factor_x", 4);
+ node_->declare_parameter("binning_factor_y", 4);
+ // Get parameters
+ node_->get_parameter("binning_factor_x", binning_factor_x_);
+ node_->get_parameter("binning_factor_y", binning_factor_y_);
}
/**
* @brief Callback used to update the head mode
*/
- //void head_mode_callback(const bitbots_msgs::msg::HeadMode::SharedPtr msg) { head_mode_ = msg->head_mode; }
+ void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr& image_msg,
+ const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg) {
+ // Convert to cv::Mat
+ cv::Mat image = cv_bridge::toCvShare(image_msg)->image;
+
+ // Do some processing
+ int bit_depth = sensor_msgs::image_encodings::bitDepth(image_msg->encoding);
+
+ int type = bit_depth == 8 ? CV_8U : CV_16U;
+
+ // Create cv::Mat for color image
+ cv::Mat color(image_msg->height, image_msg->width, CV_MAKETYPE(type, 3));
+
+ // Create cv::Mat for
+ const cv::Mat bayer(image_msg->height, image_msg->width, CV_MAKETYPE(type, 1),
+ const_cast(&image_msg->data[0]), image_msg->step);
+
+ // Get the correct conversion code
+ int code = -1;
+ if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB8 ||
+ image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB16) {
+ code = cv::COLOR_BayerBG2BGR;
+ } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR8 || // NOLINT
+ image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR16) {
+ code = cv::COLOR_BayerRG2BGR;
+ } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG8 || // NOLINT
+ image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG16) {
+ code = cv::COLOR_BayerGR2BGR;
+ } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG8 || // NOLINT
+ image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG16) {
+ code = cv::COLOR_BayerGB2BGR;
+ }
+ code += cv::COLOR_BayerBG2BGR_VNG - cv::COLOR_BayerBG2BGR;
+
+ // Debayer the image
+ cv::cvtColor(bayer, color, code);
+
+ // Perform binning by a given factor
+ cv::Mat binned(image_msg->height / binning_factor_y_, image_msg->width / binning_factor_x_, CV_MAKETYPE(type, 3));
+ cv::resize(color, binned, cv::Size(), 1.0 / binning_factor_x_, 1.0 / binning_factor_y_, cv::INTER_AREA);
+
+ // Add the binning to the camera info
+ auto new_camera_info = std::make_shared(*info_msg);
+ new_camera_info->binning_x = binning_factor_x_;
+ new_camera_info->binning_y = binning_factor_y_;
+
+ // Convert back to sensor_msgs::Image
+ cv_bridge::CvImage color_msg;
+ color_msg.header = image_msg->header;
+ color_msg.encoding = sensor_msgs::image_encodings::BGR8;
+ color_msg.image = binned;
+
+ // Publish the image
+ image_pub_->publish(color_msg.toImageMsg(), new_camera_info);
+ }
/**
* @brief A getter that returns the node
*/
std::shared_ptr get_node() { return node_; }
};
-} // namespace move_head
+} // namespace postprocessing
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
From 90706b08bf40b4482a50a3532339a813ddf7c571 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 20 Mar 2024 12:12:29 +0000
Subject: [PATCH 07/21] Minimize processing deplay
---
bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
index 79200d2fc..233f32fce 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -30,8 +30,8 @@ class PostProcessor {
transport_hints_(node_.get()),
image_sub_(std::make_unique(image_transport::create_camera_subscription(
node_.get(), "in/image_raw", std::bind(&PostProcessor::image_callback, this, _1, _2),
- transport_hints_.getTransport()))),
- image_pub_(std::make_unique(
+ transport_hints_.getTransport(), rclcpp::QoS(1).get_rmw_qos_profile()))),
+ image_pub_(std::make_unique(
image_transport::create_camera_publisher(node_.get(), "out/image_proc"))) {
// Declare parameters
node_->declare_parameter("binning_factor_x", 4);
From 1305b206112a7d9b1b4e3e5ad8a50c92a5c6dbd3 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 20 Mar 2024 13:13:03 +0000
Subject: [PATCH 08/21] Use cheaper post processing
---
bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp | 3 +--
1 file changed, 1 insertion(+), 2 deletions(-)
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
index 233f32fce..789032060 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -76,8 +76,7 @@ class PostProcessor {
} else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG8 || // NOLINT
image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG16) {
code = cv::COLOR_BayerGB2BGR;
- }
- code += cv::COLOR_BayerBG2BGR_VNG - cv::COLOR_BayerBG2BGR;
+ };
// Debayer the image
cv::cvtColor(bayer, color, code);
From 98a71ddbf194dc30d70675c6bf9bcbfe19bdec64 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 20 Mar 2024 15:31:24 +0000
Subject: [PATCH 09/21] Fix formtting issue
---
.vscode/settings.json | 4 +++-
bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp | 2 +-
2 files changed, 4 insertions(+), 2 deletions(-)
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 6bfb03ca1..269e994ee 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -190,7 +190,9 @@
"typeindex": "cpp",
"typeinfo": "cpp",
"valarray": "cpp",
- "variant": "cpp"
+ "variant": "cpp",
+ "regex": "cpp",
+ "future": "cpp"
},
// Tell the ROS extension where to find the setup.bash
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
index 789032060..dec8bf9d6 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -31,7 +31,7 @@ class PostProcessor {
image_sub_(std::make_unique(image_transport::create_camera_subscription(
node_.get(), "in/image_raw", std::bind(&PostProcessor::image_callback, this, _1, _2),
transport_hints_.getTransport(), rclcpp::QoS(1).get_rmw_qos_profile()))),
- image_pub_(std::make_unique(
+ image_pub_(std::make_unique(
image_transport::create_camera_publisher(node_.get(), "out/image_proc"))) {
// Declare parameters
node_->declare_parameter("binning_factor_x", 4);
From c14048959738e72e6bb1329142a4fd14d2bbfd38 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 20 Mar 2024 15:32:25 +0000
Subject: [PATCH 10/21] Add extrinsic imu calibration
---
.../CMakeLists.txt | 2 -
.../config/amy.yaml | 8 +-
.../config/default.yaml | 8 +-
.../config/donna.yaml | 8 +-
.../config/jack.yaml | 8 +-
.../config/melody.yaml | 8 +-
.../config/rory.yaml | 10 +-
.../extrinsic_calibration.hpp | 25 ----
.../launch/calibration.launch | 10 +-
.../src/extrinsic_calibration.cpp | 124 ++++++++++--------
.../wolfgang_description/urdf/robot.urdf | 25 ++--
11 files changed, 131 insertions(+), 105 deletions(-)
delete mode 100644 bitbots_misc/bitbots_extrinsic_calibration/include/extrinsic_calibration/extrinsic_calibration.hpp
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt b/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
index 1dfc02d76..f08aaeb3d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
+++ b/bitbots_misc/bitbots_extrinsic_calibration/CMakeLists.txt
@@ -17,8 +17,6 @@ find_package(tf2 REQUIRED)
find_package(rot_conv REQUIRED)
find_package(backward_ros REQUIRED)
-include_directories(include)
-
add_compile_options(-Wall -Werror -Wno-unused)
add_executable(extrinsic_calibration src/extrinsic_calibration.cpp)
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
index 5944a576d..93bdfd39d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
@@ -1,4 +1,10 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
+ ros__parameters:
+ offset_x: 0.0
+ offset_y: 0.0
+ offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
ros__parameters:
offset_x: 0.0
offset_y: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/default.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/default.yaml
index 5944a576d..93bdfd39d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/default.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/default.yaml
@@ -1,4 +1,10 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
+ ros__parameters:
+ offset_x: 0.0
+ offset_y: 0.0
+ offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
ros__parameters:
offset_x: 0.0
offset_y: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/donna.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/donna.yaml
index 5944a576d..93bdfd39d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/donna.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/donna.yaml
@@ -1,4 +1,10 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
+ ros__parameters:
+ offset_x: 0.0
+ offset_y: 0.0
+ offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
ros__parameters:
offset_x: 0.0
offset_y: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml
index ed0cbe9f8..60fd7357c 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml
@@ -1,5 +1,11 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
ros__parameters:
offset_x: -0.05
offset_y: 0.15
offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
+ ros__parameters:
+ offset_x: 0.0
+ offset_y: 0.0
+ offset_z: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/melody.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/melody.yaml
index 5944a576d..93bdfd39d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/melody.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/melody.yaml
@@ -1,4 +1,10 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
+ ros__parameters:
+ offset_x: 0.0
+ offset_y: 0.0
+ offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
ros__parameters:
offset_x: 0.0
offset_y: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml
index 5944a576d..fccb85d09 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml
@@ -1,5 +1,11 @@
-/bitbots_extrinsic_calibration:
+/bitbots_extrinsic_camera_calibration:
ros__parameters:
- offset_x: 0.0
+ offset_x: -0.03
offset_y: 0.0
offset_z: 0.0
+
+/bitbots_extrinsic_imu_calibration:
+ ros__parameters:
+ offset_x: -0.03
+ offset_y: 0.03
+ offset_z: 0.0
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/include/extrinsic_calibration/extrinsic_calibration.hpp b/bitbots_misc/bitbots_extrinsic_calibration/include/extrinsic_calibration/extrinsic_calibration.hpp
deleted file mode 100644
index 610cfd063..000000000
--- a/bitbots_misc/bitbots_extrinsic_calibration/include/extrinsic_calibration/extrinsic_calibration.hpp
+++ /dev/null
@@ -1,25 +0,0 @@
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-#include
-#include
-using std::placeholders::_1;
-
-class ExtrinsicCalibrationBroadcaster : public rclcpp::Node {
- public:
- ExtrinsicCalibrationBroadcaster();
- void step();
-
- private:
- OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
- std::unique_ptr broadcaster_;
- geometry_msgs::msg::Transform transform_{geometry_msgs::msg::Transform()};
- std::string parent_frame_, child_frame_;
- double offset_x_ = 0, offset_y_ = 0, offset_z_ = 0;
- rcl_interfaces::msg::SetParametersResult onSetParameters(const std::vector ¶meters);
-};
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/launch/calibration.launch b/bitbots_misc/bitbots_extrinsic_calibration/launch/calibration.launch
index d4b136cb4..6e4e4c08d 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/launch/calibration.launch
+++ b/bitbots_misc/bitbots_extrinsic_calibration/launch/calibration.launch
@@ -1,8 +1,16 @@
-
+
+
+
+
+
+
+
+
+
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp b/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
index 82342cf27..b9cd7a4e5 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
+++ b/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
@@ -1,74 +1,82 @@
-#include
-
-ExtrinsicCalibrationBroadcaster::ExtrinsicCalibrationBroadcaster() : Node("bitbots_extrinsic_calibration") {
- broadcaster_ = std::make_unique(this);
-
- this->declare_parameter("parent_frame", "camera");
- this->declare_parameter("child_frame", "camera_optical_frame");
- this->declare_parameter("offset_x", 0.0, rcl_interfaces::msg::ParameterDescriptor());
- this->declare_parameter("offset_y", 0.0);
- this->declare_parameter("offset_z", 0.0);
-
- auto parameters = this->get_parameters(this->list_parameters({}, 10).names);
- ExtrinsicCalibrationBroadcaster::onSetParameters(parameters);
-
- param_callback_handle_ =
- this->add_on_set_parameters_callback(std::bind(&ExtrinsicCalibrationBroadcaster::onSetParameters, this, _1));
-}
-
-rcl_interfaces::msg::SetParametersResult ExtrinsicCalibrationBroadcaster::onSetParameters(
- const std::vector ¶meters) {
- for (const auto ¶meter : parameters) {
- if (parameter.get_name() == "offset_x") {
- offset_x_ = parameter.as_double();
- } else if (parameter.get_name() == "offset_y") {
- offset_y_ = parameter.as_double();
- } else if (parameter.get_name() == "offset_z") {
- offset_z_ = parameter.as_double();
- } else if (parameter.get_name() == "parent_frame") {
- parent_frame_ = parameter.as_string();
- } else if (parameter.get_name() == "child_frame") {
- child_frame_ = parameter.as_string();
- } else {
- RCLCPP_DEBUG(this->get_logger(), "Unknown parameter: %s", parameter.get_name().c_str());
- }
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+using std::placeholders::_1;
+
+class ExtrinsicCalibrationBroadcaster : public rclcpp::Node {
+ public:
+ ExtrinsicCalibrationBroadcaster() : Node("bitbots_extrinsic_calibration") {
+ broadcaster_ = std::make_unique(this);
+
+ this->declare_parameter("parent_frame", "camera_optical_frame_uncalibrated");
+ this->declare_parameter("child_frame", "camera_optical_frame");
+ this->declare_parameter("offset_x", 0.0, rcl_interfaces::msg::ParameterDescriptor());
+ this->declare_parameter("offset_y", 0.0);
+ this->declare_parameter("offset_z", 0.0);
+
+ auto parameters = this->get_parameters(this->list_parameters({}, 10).names);
+ onSetParameters(parameters);
+
+ param_callback_handle_ =
+ this->add_on_set_parameters_callback(std::bind(&ExtrinsicCalibrationBroadcaster::onSetParameters, this, _1));
}
- auto base_quat = rot_conv::QuatFromEuler(-1.5708, 0.0, -1.5708);
- auto offset_quat = rot_conv::QuatFromEuler(offset_z_, offset_y_, offset_x_);
-
- auto final_quat = offset_quat * base_quat;
+ rcl_interfaces::msg::SetParametersResult onSetParameters(const std::vector ¶meters) {
+ for (const auto ¶meter : parameters) {
+ if (parameter.get_name() == "offset_x") {
+ offset_x_ = parameter.as_double();
+ } else if (parameter.get_name() == "offset_y") {
+ offset_y_ = parameter.as_double();
+ } else if (parameter.get_name() == "offset_z") {
+ offset_z_ = parameter.as_double();
+ } else if (parameter.get_name() == "parent_frame") {
+ parent_frame_ = parameter.as_string();
+ } else if (parameter.get_name() == "child_frame") {
+ child_frame_ = parameter.as_string();
+ } else {
+ RCLCPP_DEBUG(this->get_logger(), "Unknown parameter: %s", parameter.get_name().c_str());
+ }
+ }
+ auto offset_quat = rot_conv::QuatFromEuler(offset_z_, offset_y_, offset_x_);
- transform_.rotation.x = final_quat.x();
- transform_.rotation.y = final_quat.y();
- transform_.rotation.z = final_quat.z();
- transform_.rotation.w = final_quat.w();
+ transform_.rotation.x = offset_quat.x();
+ transform_.rotation.y = offset_quat.y();
+ transform_.rotation.z = offset_quat.z();
+ transform_.rotation.w = offset_quat.w();
- rcl_interfaces::msg::SetParametersResult result;
- result.successful = true;
+ geometry_msgs::msg::TransformStamped tf;
+ tf.header.stamp = this->now();
+ tf.header.frame_id = parent_frame_;
+ tf.child_frame_id = child_frame_;
+ tf.transform = transform_;
+ broadcaster_->sendTransform(tf);
- return result;
-}
+ rcl_interfaces::msg::SetParametersResult result;
+ result.successful = true;
-void ExtrinsicCalibrationBroadcaster::step() {
- rclcpp::Time now = this->now();
+ return result;
+ }
- geometry_msgs::msg::TransformStamped tf;
- tf.header.stamp = now;
- tf.header.frame_id = parent_frame_;
- tf.child_frame_id = child_frame_;
- tf.transform = transform_;
- broadcaster_->sendTransform(tf);
-}
+ private:
+ OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
+ std::unique_ptr broadcaster_;
+ geometry_msgs::msg::Transform transform_{geometry_msgs::msg::Transform()};
+ std::string parent_frame_, child_frame_;
+ double offset_x_ = 0, offset_y_ = 0, offset_z_ = 0;
+};
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared();
- rclcpp::TimerBase::SharedPtr timer =
- rclcpp::create_timer(node, node->get_clock(), rclcpp::Duration(0, 1e7), [node]() -> void { node->step(); });
-
rclcpp::experimental::executors::EventsExecutor exec;
exec.add_node(node);
exec.spin();
diff --git a/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf b/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf
index 31dc49076..b9fc59749 100644
--- a/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf
+++ b/bitbots_wolfgang/wolfgang_description/urdf/robot.urdf
@@ -192,7 +192,7 @@
-
+
@@ -374,18 +374,19 @@
-
+
+
-
+
-
+
@@ -3588,21 +3589,21 @@
+
-
+
-
+
- -->
@@ -3870,7 +3871,7 @@
-
+ truetrue
@@ -3879,12 +3880,12 @@
__default_topic__imu
- imu_frame
+ imu_frame_uncalibrated100.00.00 0 00 0 0
- imu_frame
+ imu_frame_uncalibrated0 0 0 0 0 0
From 5878686b3a8ad18a6c3be2df1c220bb02500cb5a Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 20 Mar 2024 17:41:27 +0000
Subject: [PATCH 11/21] Add calibration for amy
---
bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
index 93bdfd39d..989323e24 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
+++ b/bitbots_misc/bitbots_extrinsic_calibration/config/amy.yaml
@@ -1,11 +1,11 @@
/bitbots_extrinsic_camera_calibration:
ros__parameters:
- offset_x: 0.0
+ offset_x: -0.03
offset_y: 0.0
offset_z: 0.0
/bitbots_extrinsic_imu_calibration:
ros__parameters:
- offset_x: 0.0
- offset_y: 0.0
+ offset_x: -0.03
+ offset_y: -0.08
offset_z: 0.0
From f5a9f3cf5dceaad1c31e9a67fb2c727ec6987307 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Thu, 21 Mar 2024 15:55:24 +0000
Subject: [PATCH 12/21] Optimize head mover
---
bitbots_motion/bitbots_head_mover/src/move_head.cpp | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/bitbots_motion/bitbots_head_mover/src/move_head.cpp b/bitbots_motion/bitbots_head_mover/src/move_head.cpp
index 8d9e61ef5..70e949b1c 100644
--- a/bitbots_motion/bitbots_head_mover/src/move_head.cpp
+++ b/bitbots_motion/bitbots_head_mover/src/move_head.cpp
@@ -102,7 +102,7 @@ class HeadMover {
// Initialize subscriber for the current joint states of the robot
joint_state_subscriber_ = node_->create_subscription(
- "joint_states", 10, [this](const sensor_msgs::msg::JointState::SharedPtr msg) { joint_state_callback(msg); });
+ "joint_states", 1, [this](const sensor_msgs::msg::JointState::SharedPtr msg) { joint_state_callback(msg); });
// Create parameter listener and load initial set of parameters
param_listener_ = std::make_shared(node_);
@@ -181,7 +181,7 @@ class HeadMover {
std::bind(&HeadMover::handle_accepted, this, std::placeholders::_1));
// Initialize timer for main loop
- timer_ = rclcpp::create_timer(node_, node_->get_clock(), 10ms, [this] { behave(); });
+ timer_ = rclcpp::create_timer(node_, node_->get_clock(), 50ms, [this] { behave(); });
}
/**
@@ -689,7 +689,7 @@ class HeadMover {
// Send the motor goals to the head motors
bool success =
- send_motor_goals(head_pan, head_tilt, true, pan_speed_, tilt_speed_, current_head_pan, current_head_tilt);
+ send_motor_goals(head_pan, head_tilt, false, pan_speed_, tilt_speed_, current_head_pan, current_head_tilt);
if (success) {
// Check if we reached the current keypoint and if so, increase the index
From 1feb5ebe5d711f075168b6b95e3c464d8b7c8208 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Thu, 21 Mar 2024 15:55:36 +0000
Subject: [PATCH 13/21] Set grab strategy
---
bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml | 3 +++
1 file changed, 3 insertions(+)
diff --git a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
index 5f8f1a889..a3be7a43f 100644
--- a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
+++ b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
@@ -110,3 +110,6 @@ pylon_camera_node:
gige/inter_pkg_delay: 4000
rectification_active: false
+
+ # Only grab the latest image
+ grab_strategy: 1
From 150e0f7ca8b6766ad058030f4c4d334005e73894 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Fri, 22 Mar 2024 10:25:00 +0000
Subject: [PATCH 14/21] Add custom camera driver
---
.vscode/c_cpp_properties.json | 3 +-
.../bitbots_basler_camera/CMakeLists.txt | 12 +-
.../config/camera_settings.yaml | 184 ++++++----------
.../bitbots_basler_camera/config/default.yaml | 123 -----------
.../launch/basler_camera.launch | 16 +-
.../bitbots_basler_camera/package.xml | 3 +-
.../src/postprocessing.cpp | 200 +++++++++++++-----
7 files changed, 232 insertions(+), 309 deletions(-)
delete mode 100644 bitbots_misc/bitbots_basler_camera/config/default.yaml
diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index c08288577..2460329d7 100644
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -16,7 +16,8 @@
"/root/colcon_ws/build/**/rosidl_generator_cpp/**",
"${workspaceFolder}/**/include/**",
"/opt/ros/${env:ROS_DISTRO}/include/**",
- "/usr/include/**"
+ "/usr/include/**",
+ "/opt/pylon/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
diff --git a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
index 596badf8a..c240cf764 100644
--- a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
+++ b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
@@ -14,12 +14,20 @@ find_package(image_transport REQUIRED)
find_package(OpenCV REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
+find_package(pylon 7.1.0 REQUIRED)
+find_package(camera_info_manager REQUIRED)
+find_package(generate_parameter_library REQUIRED)
add_compile_options(-Wall -Werror -Wno-unused)
+generate_parameter_library(
+ pylon_camera_parameters # cmake target name for the parameter library
+ config/camera_settings.yaml)
+
add_executable(postprocessing src/postprocessing.cpp)
-target_link_libraries(postprocessing ${OpenCV_LIBRARIES})
+target_link_libraries(postprocessing ${OpenCV_LIBRARIES} pylon::pylon
+ pylon_camera_parameters)
ament_target_dependencies(
postprocessing
@@ -29,6 +37,8 @@ ament_target_dependencies(
image_transport
rclcpp
sensor_msgs
+ camera_info_manager
+ generate_parameter_library
OpenCV)
enable_bitbots_docs()
diff --git a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
index a3be7a43f..48cbc777f 100644
--- a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
+++ b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
@@ -1,115 +1,69 @@
-pylon_camera_node:
- ros__parameters:
- # The tf frame under which the images were published
- camera_frame: camera_optical_frame
-
- # The encoding of the pixels -- channel meaning, ordering, size
- # taken from the list of strings in include/sensor_msgs/image_encodings.h
- # The supported encodings are 'mono8', 'bgr8', 'rgb8', 'bayer_bggr8',
- # 'bayer_gbrg8' and 'bayer_rggb8'
- # Default values are 'mono8' and 'rgb8'
- image_encoding: "bayer_rggb8"
-
- # Binning factor to get downsampled images. It refers here to any camera
- # setting which combines rectangular neighborhoods of pixels into larger
- # "super-pixels." It reduces the resolution of the output image to
- # (width / binning_x) x (height / binning_y).
- # The default values binning_x = binning_y = 0 are considered the same
- # as binning_x = binning_y = 1 (no subsampling).
- # binning_x: 4
- # binning_y: 4
-
- # The desired publisher frame rate if listening to the topics.
- # This parameter can only be set once at startup
- # Calling the GrabImages-Action can result in a higher framerate
- frame_rate: 10.0
-
- # Mode of camera's shutter.
- # The supported modes are "rolling", "global" and "global_reset"
- # Default value is "" (empty) means default_shutter_mode
- shutter_mode: "global"
-
- ##########################################################################
- ######################## Image Intensity Settings ########################
- ##########################################################################
- # The following settings do *NOT* have to be set. Each camera has default
- # values which provide an automatic image adjustment resulting in valid
- # images
- ##########################################################################
-
- # The exposure time in microseconds to be set after opening the camera.
- exposure: 3000.0
-
- # The target gain in percent of the maximal value the camera supports
- # For USB-Cameras, the gain is in dB, for GigE-Cameras it is given in so
- # called 'device specific units'.
- gain: 0.55
-
- # Gamma correction of pixel intensity.
- # Adjusts the brightness of the pixel values output by the camera's sensor
- # to account for a non-linearity in the human perception of brightness or
- # of the display system (such as CRT).
- gamma: 1.0
-
- # The average intensity value of the images. It depends the exposure time
- # as well as the gain setting. If 'exposure' is provided, the interface will
- # try to reach the desired brightness by only varying the gain. (What may
- # often fail, because the range of possible exposure vaules is many
- # times higher than the gain range). If 'gain' is provided, the interface will
- # try to reach the desired brightness by only varying the exposure time. If
- # gain AND exposure are given, it is not possible to reach the brightness,
- # because both are assumed to be fix.
- # brightness: 100
-
- # Only relevant, if 'brightness' is set:
- # The brightness_continuous flag controls the auto brightness function.
- # If it is set to false, the brightness will only be reached once.
- # Hence changing light conditions lead to changing brightness values.
- # If it is set to true, the given brightness will be reached continuously,
- # trying to adapt to changing light conditions. This is only possible for
- # values in the possible auto range of the pylon API which is e.g. [50 - 205]
- # for acA2500-14um and acA1920-40gm
- # brightness_continuous: true
-
- # Only relevant, if 'brightness' is set:
- # If the camera should try to reach and / or keep the brightness, hence
- # adapting to changing light conditions, at least one of the following flags
- # must be set.
- # If both are set, the interface will use the profile that tries to keep the
- # gain at minimum to reduce white noise.
- # The exposure_auto flag indicates, that the desired brightness will be
- # reached by adapting the exposure time.
- # The gain_auto flag indicates, that the desired brightness will be
- # reached by adapting the gain.
- # exposure_auto: true
- # gain_auto: true
-
- ##########################################################################
-
- # The timeout while searching the exposure which is connected to the
- # desired brightness. For slow system this has to be increased.
- # exposure_search_timeout: 5.0
-
- # The exposure search can be limited with an upper bound. This is to prevent
- # very high exposure times and resulting timeouts.
- # A typical value for this upper bound is ~2000000us.
- # auto_exposure_upper_limit: 2000000.0
-
- # The MTU size. Only used for GigE cameras.
- # To prevent lost frames configure the camera has to be configured
- # with the MTU size the network card supports. A value greater 3000
- # should be good (1500 for RaspberryPI)
- # gige:
- gige/mtu_size: 8000
-
- # Only used for GigE cameras.
- # The inter-package delay in ticks to prevent lost frames.
- # For most of GigE-Cameras, a value of 1000 is reasonable.
- # For cameras used on a RaspberryPI this value should be set to 11772.
- # gige:
- gige/inter_pkg_delay: 4000
-
- rectification_active: false
-
- # Only grab the latest image
- grab_strategy: 1
+pylon_camera_parameters:
+ exposure:
+ type: double
+ default_value: 3000.0
+ description: "The exposure time in microseconds to be set after opening the camera."
+ validation:
+ bounds<>: [0.0, 1000000.0]
+ gain:
+ type: double
+ default_value: 0.55
+ description: "The target gain in percent of the maximal value the camera supports."
+ validation:
+ bounds<>: [0.0, 1.0]
+ gamma:
+ type: double
+ default_value: 1.0
+ description: "Gamma correction of pixel intensity."
+ validation:
+ bounds<>: [0.0, 2.0]
+ fps:
+ type: double
+ default_value: 10.0
+ read_only: true
+ description: "Target frame rate of the camera / publisher."
+ validation:
+ bounds<>: [0.0, 30.0]
+ binning_factor_x:
+ type: int
+ default_value: 4
+ read_only: true
+ description: "Binning factor to get downsampled images in x direction."
+ validation:
+ gt_eq<>: [1]
+ binning_factor_y:
+ type: int
+ default_value: 4
+ read_only: true
+ description: "Binning factor to get downsampled images in y direction."
+ validation:
+ gt_eq<>: [1]
+ camera_info_url:
+ type: string
+ default_value: ""
+ read_only: true
+ description: "The URL of the camera calibration file."
+ device_user_id:
+ type: string
+ default_value: "camera"
+ read_only: true
+ description: "The name of the camera (used to discover the camera). The name can be set in the pylon viewer."
+ camera_frame_id:
+ type: string
+ default_value: "camera_optical_frame"
+ read_only: true
+ description: "The tf frame at which the camera's optical center is located."
+ gige:
+ mtu_size:
+ type: int
+ default_value: 8000
+ description: "The MTU size for GigE cameras."
+ read_only: true
+
+ inter_pkg_delay:
+ type: int
+ default_value: 4000
+ description: "The inter-package delay in 'ticks' for GigE cameras."
+ read_only: true
+ validation:
+ bounds<>: [0, 10000]
diff --git a/bitbots_misc/bitbots_basler_camera/config/default.yaml b/bitbots_misc/bitbots_basler_camera/config/default.yaml
deleted file mode 100644
index d0c85ac72..000000000
--- a/bitbots_misc/bitbots_basler_camera/config/default.yaml
+++ /dev/null
@@ -1,123 +0,0 @@
-pylon_camera_node:
- ros__parameters:
- # The tf frame under which the images were published
- camera_frame: pylon_camera
-
- # The DeviceUserID of the camera. If empty, the first camera found in the
- # device list will be used
- device_user_id: ""
-
- # The CameraInfo URL (Uniform Resource Locator) where the optional intrinsic
- # camera calibration parameters are stored. This URL string will be parsed
- # from the ROS-CameraInfoManager:
- # http://docs.ros.org/api/camera_info_manager/html/classcamera__info__manager_
- # 1_1CameraInfoManager.html#details
- camera_info_url: ""
-
- # The encoding of the pixels -- channel meaning, ordering, size
- # taken from the list of strings in include/sensor_msgs/image_encodings.h
- # The supported encodings are 'mono8', 'bgr8', 'rgb8', 'bayer_bggr8',
- # 'bayer_gbrg8' and 'bayer_rggb8'
- # Default values are 'mono8' and 'rgb8'
- image_encoding: "bayer_rggb8"
-
- # Binning factor to get downsampled images. It refers here to any camera
- # setting which combines rectangular neighborhoods of pixels into larger
- # "super-pixels." It reduces the resolution of the output image to
- # (width / binning_x) x (height / binning_y).
- # The default values binning_x = binning_y = 0 are considered the same
- # as binning_x = binning_y = 1 (no subsampling).
- # binning_x: 4
- # binning_y: 4
-
- # The desired publisher frame rate if listening to the topics.
- # This parameter can only be set once at startup
- # Calling the GrabImages-Action can result in a higher framerate
- frame_rate: 20.0
-
- # Mode of camera's shutter.
- # The supported modes are "rolling", "global" and "global_reset"
- # Default value is "" (empty) means default_shutter_mode
- shutter_mode: "global"
-
- ##########################################################################
- ######################## Image Intensity Settings ########################
- ##########################################################################
- # The following settings do *NOT* have to be set. Each camera has default
- # values which provide an automatic image adjustment resulting in valid
- # images
- ##########################################################################
-
- # The exposure time in microseconds to be set after opening the camera.
- exposure: 2000.0
-
- # The target gain in percent of the maximal value the camera supports
- # For USB-Cameras, the gain is in dB, for GigE-Cameras it is given in so
- # called 'device specific units'.
- gain: 0.4
-
- # Gamma correction of pixel intensity.
- # Adjusts the brightness of the pixel values output by the camera's sensor
- # to account for a non-linearity in the human perception of brightness or
- # of the display system (such as CRT).
- # gamma: 1.0
-
- # The average intensity value of the images. It depends the exposure time
- # as well as the gain setting. If 'exposure' is provided, the interface will
- # try to reach the desired brightness by only varying the gain. (What may
- # often fail, because the range of possible exposure vaules is many
- # times higher than the gain range). If 'gain' is provided, the interface will
- # try to reach the desired brightness by only varying the exposure time. If
- # gain AND exposure are given, it is not possible to reach the brightness,
- # because both are assumed to be fix.
- # brightness: 100
-
- # Only relevant, if 'brightness' is set:
- # The brightness_continuous flag controls the auto brightness function.
- # If it is set to false, the brightness will only be reached once.
- # Hence changing light conditions lead to changing brightness values.
- # If it is set to true, the given brightness will be reached continuously,
- # trying to adapt to changing light conditions. This is only possible for
- # values in the possible auto range of the pylon API which is e.g. [50 - 205]
- # for acA2500-14um and acA1920-40gm
- # brightness_continuous: true
-
- # Only relevant, if 'brightness' is set:
- # If the camera should try to reach and / or keep the brightness, hence
- # adapting to changing light conditions, at least one of the following flags
- # must be set.
- # If both are set, the interface will use the profile that tries to keep the
- # gain at minimum to reduce white noise.
- # The exposure_auto flag indicates, that the desired brightness will be
- # reached by adapting the exposure time.
- # The gain_auto flag indicates, that the desired brightness will be
- # reached by adapting the gain.
- # exposure_auto: true
- # gain_auto: true
-
- ##########################################################################
-
- # The timeout while searching the exposure which is connected to the
- # desired brightness. For slow system this has to be increased.
- # exposure_search_timeout: 5.0
-
- # The exposure search can be limited with an upper bound. This is to prevent
- # very high exposure times and resulting timeouts.
- # A typical value for this upper bound is ~2000000us.
- # auto_exposure_upper_limit: 2000000.0
-
- # The MTU size. Only used for GigE cameras.
- # To prevent lost frames configure the camera has to be configured
- # with the MTU size the network card supports. A value greater 3000
- # should be good (1500 for RaspberryPI)
- # gige:
- gige/mtu_size: 1500
-
- # Only used for GigE cameras.
- # The inter-package delay in ticks to prevent lost frames.
- # For most of GigE-Cameras, a value of 1000 is reasonable.
- # For cameras used on a RaspberryPI this value should be set to 11772.
- # gige:
- #inter_pkg_delay: 131072
-
- reactification_active: false
diff --git a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
index 8c297b0d9..ba5173a9b 100644
--- a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
+++ b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
@@ -3,22 +3,8 @@
-
-
-
+
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/bitbots_misc/bitbots_basler_camera/package.xml b/bitbots_misc/bitbots_basler_camera/package.xml
index 7f249425b..7b26f6f4f 100644
--- a/bitbots_misc/bitbots_basler_camera/package.xml
+++ b/bitbots_misc/bitbots_basler_camera/package.xml
@@ -16,9 +16,10 @@
cv_bridgeimage_transportlibopencv-dev
- pylon_ros2_camera_wrapperrclcppsensor_msgs
+ camera_info_manager
+ generate_parameter_libraryament_cmake
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
index dec8bf9d6..519399a12 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
@@ -1,3 +1,9 @@
+#include
+#include
+#include
+
+#include
+#include
#include
#include
#include
@@ -10,7 +16,10 @@
#include
#include
+#include "pylon_camera_parameters.hpp"
+
using std::placeholders::_1, std::placeholders::_2;
+using namespace Pylon;
namespace postprocessing {
@@ -18,86 +27,171 @@ class PostProcessor {
std::shared_ptr node_;
image_transport::TransportHints transport_hints_;
- std::unique_ptr image_sub_;
std::unique_ptr image_pub_;
+ rclcpp::TimerBase::SharedPtr timer_;
+
+ std::unique_ptr camera_info_manager_;
+
+ std::unique_ptr camera_;
+
+ Pylon::PylonAutoInitTerm autoInitTerm;
- int binning_factor_x_ = 1;
- int binning_factor_y_ = 1;
+ std::unique_ptr param_listener_;
+ pylon_camera_parameters::Params config_;
public:
PostProcessor()
: node_(std::make_shared("post_processor")),
transport_hints_(node_.get()),
- image_sub_(std::make_unique(image_transport::create_camera_subscription(
- node_.get(), "in/image_raw", std::bind(&PostProcessor::image_callback, this, _1, _2),
- transport_hints_.getTransport(), rclcpp::QoS(1).get_rmw_qos_profile()))),
image_pub_(std::make_unique(
- image_transport::create_camera_publisher(node_.get(), "out/image_proc"))) {
- // Declare parameters
- node_->declare_parameter("binning_factor_x", 4);
- node_->declare_parameter("binning_factor_y", 4);
-
- // Get parameters
- node_->get_parameter("binning_factor_x", binning_factor_x_);
- node_->get_parameter("binning_factor_y", binning_factor_y_);
+ image_transport::create_camera_publisher(node_.get(), "camera/image_proc"))) {
+ // Load parameters
+ param_listener_ = std::make_unique(node_);
+ config_ = param_listener_->get_params();
+
+ // Set up camera info manager
+ camera_info_manager_ = std::make_unique(node_.get(), config_.device_user_id,
+ config_.camera_info_url);
+
+ try {
+ // List all available devices
+ Pylon::DeviceInfoList_t devices;
+ CTlFactory::GetInstance().EnumerateDevices(devices);
+
+ // Print all devices and their names
+ for (size_t i = 0; i < devices.size(); ++i) {
+ RCLCPP_INFO(node_->get_logger(), "Device %ld: %s (%s)", i, devices[i].GetFriendlyName().c_str(),
+ devices[i].GetModelName().c_str());
+ }
+
+ // Initialize the camera
+ initilize_camera();
+
+ } catch (GenICam::GenericException& e) {
+ // Error handling.
+ RCLCPP_ERROR(node_->get_logger(), "An exception occurred: %s", e.GetDescription());
+ RCLCPP_ERROR(node_->get_logger(), "Could not initialize camera");
+ exit(1);
+ }
+
+ // Setup timer for publishing
+ timer_ = node_->create_wall_timer(std::chrono::duration(1.0 / config_.fps),
+ std::bind(&PostProcessor::timer_callback, this));
}
- /**
- * @brief Callback used to update the head mode
- */
- void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr& image_msg,
- const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg) {
- // Convert to cv::Mat
- cv::Mat image = cv_bridge::toCvShare(image_msg)->image;
+ void initilize_camera() {
+ // Set up the camera
+ camera_ = std::make_unique(CTlFactory::GetInstance().CreateFirstDevice());
+
+ // Wait for the camera to be ready
+ camera_->Open();
- // Do some processing
- int bit_depth = sensor_msgs::image_encodings::bitDepth(image_msg->encoding);
+ // Print the model name of the camera.
+ RCLCPP_INFO(node_->get_logger(), "Using device '%s'", camera_->GetDeviceInfo().GetFriendlyName().c_str());
- int type = bit_depth == 8 ? CV_8U : CV_16U;
+ // Set static camera parameters
+ camera_->ShutterMode.SetValue(Basler_UniversalCameraParams::ShutterModeEnums::ShutterMode_Global);
+ camera_->Width.SetToMaximum();
+ camera_->Height.SetToMaximum();
+ camera_->PixelFormat.SetValue(Basler_UniversalCameraParams::PixelFormat_BayerRG8);
+ camera_->BalanceWhiteAuto.SetValue(
+ Basler_UniversalCameraParams::BalanceWhiteAutoEnums::BalanceWhiteAuto_Continuous);
+
+ // Set MTU and inter-package delay
+ camera_->GevSCPSPacketSize.SetValue(config_.gige.mtu_size);
+ camera_->GevSCPD.SetValue(config_.gige.inter_pkg_delay);
+
+ // Set to manual acquisition mode
+ camera_->AcquisitionMode.SetValue(Basler_UniversalCameraParams::AcquisitionModeEnums::AcquisitionMode_SingleFrame);
+
+ // Set the camera parameters
+ apply_camera_parameters();
+ }
+
+ void apply_camera_parameters() {
+ // Set the camera parameters
+ camera_->Gain.SetValue(config_.gain);
+ camera_->ExposureTime.SetValue(config_.exposure);
+ camera_->Gamma.SetValue(config_.gamma);
+ }
+
+ void timer_callback() {
+ // This smart pointer will receive the grab result data.
+ CGrabResultPtr ptrGrabResult;
+
+ // Field to store the trigger time
+ rclcpp::Time trigger_time;
+
+ try {
+ // Check if the config has changed
+ if (param_listener_->is_old(config_)) {
+ // Update the camera parameters
+ config_ = param_listener_->get_params();
+ // Apply the new camera parameters
+ apply_camera_parameters();
+ }
+
+ // Try to reinitialize the camera if the connection is lost
+ if (!camera_->IsOpen() or camera_->IsCameraDeviceRemoved()) {
+ RCLCPP_WARN(node_->get_logger(), "Camera connection lost. Reinitializing camera");
+ initilize_camera();
+ }
+
+ // Cancel all pending grabs
+ camera_->StopGrabbing();
+
+ // Start frame acquisition
+ camera_->StartGrabbing(1, GrabStrategy_LatestImageOnly);
+
+ // Store the current time
+ trigger_time = node_->now();
+
+ // Wait for an image and then retrieve it. A timeout of 5000 ms is used.
+ camera_->RetrieveResult(1000, ptrGrabResult, TimeoutHandling_ThrowException);
+
+ // Image grabbed successfully?
+ if (!ptrGrabResult->GrabSucceeded()) {
+ RCLCPP_ERROR(node_->get_logger(), "Error: %x %s", ptrGrabResult->GetErrorCode(),
+ ptrGrabResult->GetErrorDescription().c_str());
+ return;
+ }
+
+ } catch (GenICam::GenericException& e) {
+ // Error handling.
+ RCLCPP_ERROR(node_->get_logger(), "An exception occurred: %s", e.GetDescription());
+ return;
+ }
+
+ // Convert to cv::Mat
+ cv::Mat image(ptrGrabResult->GetHeight(), ptrGrabResult->GetWidth(), CV_8UC1, (uint8_t*)ptrGrabResult->GetBuffer());
// Create cv::Mat for color image
- cv::Mat color(image_msg->height, image_msg->width, CV_MAKETYPE(type, 3));
-
- // Create cv::Mat for
- const cv::Mat bayer(image_msg->height, image_msg->width, CV_MAKETYPE(type, 1),
- const_cast(&image_msg->data[0]), image_msg->step);
-
- // Get the correct conversion code
- int code = -1;
- if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB8 ||
- image_msg->encoding == sensor_msgs::image_encodings::BAYER_RGGB16) {
- code = cv::COLOR_BayerBG2BGR;
- } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR8 || // NOLINT
- image_msg->encoding == sensor_msgs::image_encodings::BAYER_BGGR16) {
- code = cv::COLOR_BayerRG2BGR;
- } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG8 || // NOLINT
- image_msg->encoding == sensor_msgs::image_encodings::BAYER_GBRG16) {
- code = cv::COLOR_BayerGR2BGR;
- } else if (image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG8 || // NOLINT
- image_msg->encoding == sensor_msgs::image_encodings::BAYER_GRBG16) {
- code = cv::COLOR_BayerGB2BGR;
- };
+ cv::Mat color(image.size(), CV_MAKETYPE(CV_8U, 3));
// Debayer the image
- cv::cvtColor(bayer, color, code);
+ cv::cvtColor(image, color, cv::COLOR_BayerBG2BGR);
// Perform binning by a given factor
- cv::Mat binned(image_msg->height / binning_factor_y_, image_msg->width / binning_factor_x_, CV_MAKETYPE(type, 3));
- cv::resize(color, binned, cv::Size(), 1.0 / binning_factor_x_, 1.0 / binning_factor_y_, cv::INTER_AREA);
+ cv::Mat binned(image.size().height / config_.binning_factor_y, image.size().width / config_.binning_factor_x,
+ CV_MAKETYPE(CV_8U, 3));
+ cv::resize(color, binned, cv::Size(), 1.0 / config_.binning_factor_x, 1.0 / config_.binning_factor_y,
+ cv::INTER_AREA);
// Add the binning to the camera info
- auto new_camera_info = std::make_shared(*info_msg);
- new_camera_info->binning_x = binning_factor_x_;
- new_camera_info->binning_y = binning_factor_y_;
+ auto camera_info = std::make_shared(camera_info_manager_->getCameraInfo());
+ camera_info->binning_x = config_.binning_factor_x;
+ camera_info->binning_y = config_.binning_factor_y;
+ camera_info->header.frame_id = config_.camera_frame_id;
+ camera_info->header.stamp = trigger_time;
// Convert back to sensor_msgs::Image
cv_bridge::CvImage color_msg;
- color_msg.header = image_msg->header;
+ color_msg.header = camera_info->header;
color_msg.encoding = sensor_msgs::image_encodings::BGR8;
color_msg.image = binned;
// Publish the image
- image_pub_->publish(color_msg.toImageMsg(), new_camera_info);
+ image_pub_->publish(color_msg.toImageMsg(), camera_info);
}
/**
From d535474a57431bb1d2bce455dad5ae0c3843f473 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Fri, 22 Mar 2024 14:42:30 +0000
Subject: [PATCH 15/21] Add custom basler driver
---
.github/workflows/ci.yml | 2 +-
.../bitbots_basler_camera/CMakeLists.txt | 8 +--
.../config/camera_settings.yaml | 16 ++----
.../launch/basler_camera.launch | 2 +-
.../bitbots_basler_camera/package.xml | 2 +-
.../{postprocessing.cpp => basler_camera.cpp} | 57 ++++++++++++-------
.../bitbots_containers/hlvs/Dockerfile | 2 +-
scripts/make_basler.sh | 24 +-------
sync_includes_wolfgang_nuc.yaml | 1 -
workspace.repos | 4 --
10 files changed, 52 insertions(+), 66 deletions(-)
rename bitbots_misc/bitbots_basler_camera/src/{postprocessing.cpp => basler_camera.cpp} (81%)
diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index 6b352bc39..7f7a39059 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -45,5 +45,5 @@ jobs:
. /opt/ros/iron/setup.sh
. install/setup.sh
# Run tests for all packages
- colcon test --packages-skip-regex pylon --event-handlers console_direct+ --return-code-on-test-failure --parallel-workers 1
+ colcon test --event-handlers console_direct+ --return-code-on-test-failure --parallel-workers 1
working-directory: /colcon_ws
diff --git a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
index c240cf764..bc2f79f7c 100644
--- a/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
+++ b/bitbots_misc/bitbots_basler_camera/CMakeLists.txt
@@ -24,13 +24,13 @@ generate_parameter_library(
pylon_camera_parameters # cmake target name for the parameter library
config/camera_settings.yaml)
-add_executable(postprocessing src/postprocessing.cpp)
+add_executable(basler_camera src/basler_camera.cpp)
-target_link_libraries(postprocessing ${OpenCV_LIBRARIES} pylon::pylon
+target_link_libraries(basler_camera ${OpenCV_LIBRARIES} pylon::pylon
pylon_camera_parameters)
ament_target_dependencies(
- postprocessing
+ basler_camera
ament_cmake
bitbots_docs
cv_bridge
@@ -43,7 +43,7 @@ ament_target_dependencies(
enable_bitbots_docs()
-install(TARGETS postprocessing DESTINATION lib/${PROJECT_NAME})
+install(TARGETS basler_camera DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
diff --git a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
index 48cbc777f..44174421b 100644
--- a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
+++ b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
@@ -6,17 +6,11 @@ pylon_camera_parameters:
validation:
bounds<>: [0.0, 1000000.0]
gain:
- type: double
- default_value: 0.55
+ type: int
+ default_value: 200
description: "The target gain in percent of the maximal value the camera supports."
validation:
- bounds<>: [0.0, 1.0]
- gamma:
- type: double
- default_value: 1.0
- description: "Gamma correction of pixel intensity."
- validation:
- bounds<>: [0.0, 2.0]
+ bounds<>: [0, 360]
fps:
type: double
default_value: 10.0
@@ -56,13 +50,13 @@ pylon_camera_parameters:
gige:
mtu_size:
type: int
- default_value: 8000
+ default_value: 9000
description: "The MTU size for GigE cameras."
read_only: true
inter_pkg_delay:
type: int
- default_value: 4000
+ default_value: 1000
description: "The inter-package delay in 'ticks' for GigE cameras."
read_only: true
validation:
diff --git a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
index ba5173a9b..56263a669 100644
--- a/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
+++ b/bitbots_misc/bitbots_basler_camera/launch/basler_camera.launch
@@ -3,7 +3,7 @@
-
+
diff --git a/bitbots_misc/bitbots_basler_camera/package.xml b/bitbots_misc/bitbots_basler_camera/package.xml
index 7b26f6f4f..db8df33e8 100644
--- a/bitbots_misc/bitbots_basler_camera/package.xml
+++ b/bitbots_misc/bitbots_basler_camera/package.xml
@@ -3,7 +3,7 @@
bitbots_basler_camera1.0.0
- This sets up the basler camera
+ This contains the interface between the Basler camera's pylon SDK and ROS2. In addtion to that is also applies some postprocessing (debayering, downsampling) to the images.Marc BestmannHamburg Bit-Bots
diff --git a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp b/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
similarity index 81%
rename from bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
rename to bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
index 519399a12..023649005 100644
--- a/bitbots_misc/bitbots_basler_camera/src/postprocessing.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
@@ -34,6 +34,8 @@ class PostProcessor {
std::unique_ptr camera_;
+ double camera_tick_frequency_ = 1;
+
Pylon::PylonAutoInitTerm autoInitTerm;
std::unique_ptr param_listener_;
@@ -86,9 +88,18 @@ class PostProcessor {
// Wait for the camera to be ready
camera_->Open();
- // Print the model name of the camera.
+ // Print the name of the camera.
RCLCPP_INFO(node_->get_logger(), "Using device '%s'", camera_->GetDeviceInfo().GetFriendlyName().c_str());
+ // Set MTU and inter-package delay
+ camera_->GevSCPSPacketSize.SetValue(config_.gige.mtu_size);
+ camera_->GevSCPD.SetValue(config_.gige.inter_pkg_delay);
+
+ camera_->ClearBufferModeEnable();
+
+ // Set the camera parameters
+ apply_camera_parameters();
+
// Set static camera parameters
camera_->ShutterMode.SetValue(Basler_UniversalCameraParams::ShutterModeEnums::ShutterMode_Global);
camera_->Width.SetToMaximum();
@@ -97,22 +108,22 @@ class PostProcessor {
camera_->BalanceWhiteAuto.SetValue(
Basler_UniversalCameraParams::BalanceWhiteAutoEnums::BalanceWhiteAuto_Continuous);
- // Set MTU and inter-package delay
- camera_->GevSCPSPacketSize.SetValue(config_.gige.mtu_size);
- camera_->GevSCPD.SetValue(config_.gige.inter_pkg_delay);
-
// Set to manual acquisition mode
- camera_->AcquisitionMode.SetValue(Basler_UniversalCameraParams::AcquisitionModeEnums::AcquisitionMode_SingleFrame);
+ camera_->AcquisitionMode.SetValue(Basler_UniversalCameraParams::AcquisitionModeEnums::AcquisitionMode_Continuous);
- // Set the camera parameters
- apply_camera_parameters();
+ // Get the camera frequency
+ camera_tick_frequency_ = camera_->GevTimestampTickFrequency();
+
+ // Start grabbing
+ camera_->StartGrabbing(GrabStrategy_LatestImageOnly);
}
void apply_camera_parameters() {
// Set the camera parameters
- camera_->Gain.SetValue(config_.gain);
- camera_->ExposureTime.SetValue(config_.exposure);
- camera_->Gamma.SetValue(config_.gamma);
+ camera_->GainAuto.SetValue(Basler_UniversalCameraParams::GainAutoEnums::GainAuto_Off);
+ camera_->ExposureAuto.SetValue(Basler_UniversalCameraParams::ExposureAutoEnums::ExposureAuto_Off);
+ camera_->GainRaw.SetValue(config_.gain);
+ camera_->ExposureTimeAbs.SetValue(config_.exposure);
}
void timer_callback() {
@@ -137,17 +148,17 @@ class PostProcessor {
initilize_camera();
}
- // Cancel all pending grabs
- camera_->StopGrabbing();
+ // Get current camera time
+ camera_->GevTimestampControlLatch();
+ auto camera_time_stamp_at_capture = (__int128_t)camera_->GevTimestampValue();
+ camera_->GevTimestampControlLatchReset();
+ auto ros_time_stamp_at_capture = node_->now();
// Start frame acquisition
- camera_->StartGrabbing(1, GrabStrategy_LatestImageOnly);
-
- // Store the current time
- trigger_time = node_->now();
+ camera_->ExecuteSoftwareTrigger();
// Wait for an image and then retrieve it. A timeout of 5000 ms is used.
- camera_->RetrieveResult(1000, ptrGrabResult, TimeoutHandling_ThrowException);
+ camera_->RetrieveResult(100, ptrGrabResult, TimeoutHandling_ThrowException);
// Image grabbed successfully?
if (!ptrGrabResult->GrabSucceeded()) {
@@ -156,6 +167,10 @@ class PostProcessor {
return;
}
+ // Adjust the time stamp of the image
+ auto image_camera_stamp = (__int128_t)ptrGrabResult->GetTimeStamp();
+ auto image_age_in_seconds = (image_camera_stamp - camera_time_stamp_at_capture) / camera_tick_frequency_;
+ trigger_time = ros_time_stamp_at_capture + rclcpp::Duration::from_seconds(image_age_in_seconds);
} catch (GenICam::GenericException& e) {
// Error handling.
RCLCPP_ERROR(node_->get_logger(), "An exception occurred: %s", e.GetDescription());
@@ -203,7 +218,11 @@ class PostProcessor {
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
- rclcpp::experimental::executors::EventsExecutor exec;
+ rclcpp::experimental::executors::EventsExecutor exec = rclcpp::experimental::executors::EventsExecutor(
+ std::make_unique(),
+ true,
+ rclcpp::ExecutorOptions());
+
auto post_processor = std::make_shared();
exec.add_node(post_processor->get_node());
exec.spin();
diff --git a/bitbots_misc/bitbots_containers/hlvs/Dockerfile b/bitbots_misc/bitbots_containers/hlvs/Dockerfile
index 2affe1c26..71ef58d4c 100644
--- a/bitbots_misc/bitbots_containers/hlvs/Dockerfile
+++ b/bitbots_misc/bitbots_containers/hlvs/Dockerfile
@@ -63,7 +63,7 @@ RUN cd src/bitbots_main && \
rm -rf lib/udp_bridge bitbots_misc/bitbots_containers \
lib/dynamic_stack_decider/dynamic_stack_decider_visualization bitbots_lowlevel \
bitbots_wolfgang/wolfgang_pybullet_sim lib/DynamixelSDK lib/dynamixel-workbench \
- bitbots_misc/bitbots_basler_camera lib/pylon-ros-camera && \
+ bitbots_misc/bitbots_basler_camera && \
sed -i '/plotjuggler/d' bitbots_motion/bitbots_quintic_walk/package.xml && \
sed -i '/run_depend/d' bitbots_wolfgang/wolfgang_moveit_config/package.xml
diff --git a/scripts/make_basler.sh b/scripts/make_basler.sh
index acd6e9735..2bb77c08b 100755
--- a/scripts/make_basler.sh
+++ b/scripts/make_basler.sh
@@ -7,12 +7,8 @@
PYLON_DOWNLOAD_URL="https://www2.baslerweb.com/media/downloads/software/pylon_software/pylon_7_4_0_14900_linux_x86_64_debs.tar.gz"
PYLON_VERSION="7.4.0"
-# Similar to the pylon driver we also need to download the blaze supplementary package.
-BLAZE_DOWNLOAD_URL="https://www2.baslerweb.com/media/downloads/software/tof_software/pylon-supplementary-package-for-blaze-1.5.0.def07388_amd64.deb"
-BLAZE_VERSION="1.5.0"
-
# Check let the user confirm that they read the license agreement on the basler website and agree with it.
-echo "You need to confirm that you read the license agreements for pylon $PYLON_VERSION and the blaze supplementary package $BLAZE_VERSION on the basler download page (https://www.baslerweb.com/en/downloads/software-downloads/) and agree with it."
+echo "You need to confirm that you read the license agreements for pylon $PYLON_VERSION on the basler download page (https://www.baslerweb.com/en/downloads/software-downloads/) and agree with it."
# Check --ci flag for automatic confirmation in the ci
if [[ $1 == "--ci" ]]; then
@@ -58,21 +54,3 @@ else
# Install the pylon driver
sudo apt-get install /tmp/pylon/pylon_${PYLON_VERSION}*.deb -y
fi
-
-# Check if the correct blaze supplementary package BLAZE_VERSION is installed (apt)
-if apt list pylon-supplementary-package-for-blaze --installed | grep -q $BLAZE_VERSION; then
- echo "Blaze supplementary package $BLAZE_VERSION is already installed."
-else
- echo "Blaze supplementary package $BLAZE_VERSION is not installed. Installing..."
- # Check if we have an internet connection
- check_internet_connection $1
- # Check if the url exist
- if ! curl --output /dev/null --silent --head --fail "$BLAZE_DOWNLOAD_URL"; then
- echo "Blaze download url does not exist. Please check the url and update the 'BLAZE_DOWNLOAD_URL' variable in the 'make_basler.sh' script. The website might have changed."
- exit 1
- fi
- # Download the blaze supplementary package to temp folder
- wget --no-verbose $SHOW_PROGRESS $BLAZE_DOWNLOAD_URL -O /tmp/pylon-blaze-supplementary-package_${BLAZE_VERSION}.deb
- # Install the blaze supplementary package
- sudo apt-get install /tmp/pylon-blaze-supplementary-package_${BLAZE_VERSION}*.deb -y
-fi
diff --git a/sync_includes_wolfgang_nuc.yaml b/sync_includes_wolfgang_nuc.yaml
index a212b8f5a..d08677309 100644
--- a/sync_includes_wolfgang_nuc.yaml
+++ b/sync_includes_wolfgang_nuc.yaml
@@ -55,7 +55,6 @@ include:
- imu_tools
- ipm
- particle_filter
- - pylon-ros-camera
- ros2_numpy
- ros2_python_extension
- soccer_ipm
diff --git a/workspace.repos b/workspace.repos
index 3d85c349b..7f19dfe07 100644
--- a/workspace.repos
+++ b/workspace.repos
@@ -58,10 +58,6 @@ repositories:
type: git
url: git@github.com:ros-sports/ipm.git
version: rolling
- lib/pylon-ros-camera:
- type: git
- url: git@github.com:basler/pylon-ros-camera.git
- version: humble
lib/ros2_numpy:
type: git
url: git@github.com:Bit-Bots/ros2_numpy.git
From 80b8eb3cf699f1e9e190e155461d025a50cc4270 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Fri, 22 Mar 2024 15:32:35 +0000
Subject: [PATCH 16/21] Rename class and discover camera by name
---
.../config/camera_settings.yaml | 8 ++-
.../src/basler_camera.cpp | 51 +++++++++++--------
2 files changed, 38 insertions(+), 21 deletions(-)
diff --git a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
index 44174421b..0211d516e 100644
--- a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
+++ b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
@@ -37,16 +37,22 @@ pylon_camera_parameters:
default_value: ""
read_only: true
description: "The URL of the camera calibration file."
+ validation:
+ not_empty<>: []
device_user_id:
type: string
- default_value: "camera"
+ default_value: ""
read_only: true
description: "The name of the camera (used to discover the camera). The name can be set in the pylon viewer."
+ validation:
+ not_empty<>: []
camera_frame_id:
type: string
default_value: "camera_optical_frame"
read_only: true
description: "The tf frame at which the camera's optical center is located."
+ validation:
+ not_empty<>: []
gige:
mtu_size:
type: int
diff --git a/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp b/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
index 023649005..009c87cd1 100644
--- a/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
+++ b/bitbots_misc/bitbots_basler_camera/src/basler_camera.cpp
@@ -21,7 +21,7 @@
using std::placeholders::_1, std::placeholders::_2;
using namespace Pylon;
-namespace postprocessing {
+namespace basler_camera {
class PostProcessor {
std::shared_ptr node_;
@@ -56,16 +56,6 @@ class PostProcessor {
config_.camera_info_url);
try {
- // List all available devices
- Pylon::DeviceInfoList_t devices;
- CTlFactory::GetInstance().EnumerateDevices(devices);
-
- // Print all devices and their names
- for (size_t i = 0; i < devices.size(); ++i) {
- RCLCPP_INFO(node_->get_logger(), "Device %ld: %s (%s)", i, devices[i].GetFriendlyName().c_str(),
- devices[i].GetModelName().c_str());
- }
-
// Initialize the camera
initilize_camera();
@@ -82,15 +72,38 @@ class PostProcessor {
}
void initilize_camera() {
+ // List all available devices
+ Pylon::DeviceInfoList_t devices;
+ CTlFactory::GetInstance().EnumerateDevices(devices);
+
+ // The device user id of the camera we want to use
+ std::optional our_device_info;
+
+ // Print all devices and their names
+ for (auto device : devices) {
+ RCLCPP_INFO(node_->get_logger(), "Device: %s (%s)", device.GetFriendlyName().c_str(),
+ device.GetModelName().c_str());
+ // Check if the device has a user defined name and if it is the one we want to use
+ if (device.GetUserDefinedName().compare(config_.device_user_id.c_str()) == 0) {
+ our_device_info = device;
+ }
+ }
+
+ // Check if the device was found
+ if (!our_device_info) {
+ RCLCPP_ERROR(node_->get_logger(), "Could not find device with user id '%s'", config_.device_user_id.c_str());
+ return;
+ } else {
+ RCLCPP_INFO(node_->get_logger(), "Using device user id '%s'", config_.device_user_id.c_str());
+ }
+
// Set up the camera
- camera_ = std::make_unique(CTlFactory::GetInstance().CreateFirstDevice());
+ camera_ = std::make_unique(
+ CTlFactory::GetInstance().CreateDevice(our_device_info.value()));
// Wait for the camera to be ready
camera_->Open();
- // Print the name of the camera.
- RCLCPP_INFO(node_->get_logger(), "Using device '%s'", camera_->GetDeviceInfo().GetFriendlyName().c_str());
-
// Set MTU and inter-package delay
camera_->GevSCPSPacketSize.SetValue(config_.gige.mtu_size);
camera_->GevSCPD.SetValue(config_.gige.inter_pkg_delay);
@@ -214,16 +227,14 @@ class PostProcessor {
*/
std::shared_ptr get_node() { return node_; }
};
-} // namespace postprocessing
+} // namespace basler_camera
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
rclcpp::experimental::executors::EventsExecutor exec = rclcpp::experimental::executors::EventsExecutor(
- std::make_unique(),
- true,
- rclcpp::ExecutorOptions());
+ std::make_unique(), true, rclcpp::ExecutorOptions());
- auto post_processor = std::make_shared();
+ auto post_processor = std::make_shared();
exec.add_node(post_processor->get_node());
exec.spin();
rclcpp::shutdown();
From e80e58088980fa942fadda2fcab980b5b4c8e8f1 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Fri, 22 Mar 2024 17:33:48 +0000
Subject: [PATCH 17/21] Tune path planning
---
.../bitbots_path_planning/config/path_planning.yaml | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml b/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
index f4709658e..2101a8d55 100644
--- a/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
+++ b/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
@@ -21,9 +21,9 @@ bitbots_path_planning:
max_rotation_vel: 0.4
max_vel_x: 0.1
min_vel_x: -0.05
- max_vel_y: 0.04
- smoothing_k: 0.03
+ max_vel_y: 0.025
+ smoothing_k: 0.05
rotation_i_factor: 0.0
- rotation_slow_down_factor: 0.4
+ rotation_slow_down_factor: 2.2
translation_slow_down_factor: 0.5
orient_to_goal_distance: 1.0
From b7913f00d4aad0ff9fabf8417a1e77a6f359b10b Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 27 Mar 2024 07:45:03 +0100
Subject: [PATCH 18/21] Update bitbots_misc/bitbots_basler_camera/package.xml
Co-authored-by: Jan Gutsche <34797331+jaagut@users.noreply.github.com>
---
bitbots_misc/bitbots_basler_camera/package.xml | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/bitbots_misc/bitbots_basler_camera/package.xml b/bitbots_misc/bitbots_basler_camera/package.xml
index db8df33e8..88508bfbe 100644
--- a/bitbots_misc/bitbots_basler_camera/package.xml
+++ b/bitbots_misc/bitbots_basler_camera/package.xml
@@ -3,7 +3,7 @@
bitbots_basler_camera1.0.0
- This contains the interface between the Basler camera's pylon SDK and ROS2. In addtion to that is also applies some postprocessing (debayering, downsampling) to the images.
+ This contains the interface between the Basler camera's pylon SDK and ROS 2. In addtion to that is also applies some postprocessing (debayering, downsampling) to the images.Marc BestmannHamburg Bit-Bots
From f8e96fc835acfa106257e38bedf1d429abc5357e Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 27 Mar 2024 06:50:27 +0000
Subject: [PATCH 19/21] apply feedback
---
.../bitbots_basler_camera/config/camera_settings.yaml | 2 +-
.../src/extrinsic_calibration.cpp | 2 +-
bitbots_misc/bitbots_ipm/launch/ipm.launch | 6 +++---
.../bitbots_path_planning/config/path_planning.yaml | 2 +-
4 files changed, 6 insertions(+), 6 deletions(-)
diff --git a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
index 0211d516e..fc1d0c997 100644
--- a/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
+++ b/bitbots_misc/bitbots_basler_camera/config/camera_settings.yaml
@@ -8,7 +8,7 @@ pylon_camera_parameters:
gain:
type: int
default_value: 200
- description: "The target gain in percent of the maximal value the camera supports."
+ description: "The target raw gain of the camera sensor (similar to ISO)."
validation:
bounds<>: [0, 360]
fps:
diff --git a/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp b/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
index b9cd7a4e5..1530622d4 100644
--- a/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
+++ b/bitbots_misc/bitbots_extrinsic_calibration/src/extrinsic_calibration.cpp
@@ -17,7 +17,7 @@ class ExtrinsicCalibrationBroadcaster : public rclcpp::Node {
this->declare_parameter("parent_frame", "camera_optical_frame_uncalibrated");
this->declare_parameter("child_frame", "camera_optical_frame");
- this->declare_parameter("offset_x", 0.0, rcl_interfaces::msg::ParameterDescriptor());
+ this->declare_parameter("offset_x", 0.0);
this->declare_parameter("offset_y", 0.0);
this->declare_parameter("offset_z", 0.0);
diff --git a/bitbots_misc/bitbots_ipm/launch/ipm.launch b/bitbots_misc/bitbots_ipm/launch/ipm.launch
index a080e5361..a44ac382e 100644
--- a/bitbots_misc/bitbots_ipm/launch/ipm.launch
+++ b/bitbots_misc/bitbots_ipm/launch/ipm.launch
@@ -1,9 +1,9 @@
-
-
-
+
+
+
diff --git a/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml b/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
index 2101a8d55..11ae07cf1 100644
--- a/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
+++ b/bitbots_navigation/bitbots_path_planning/config/path_planning.yaml
@@ -24,6 +24,6 @@ bitbots_path_planning:
max_vel_y: 0.025
smoothing_k: 0.05
rotation_i_factor: 0.0
- rotation_slow_down_factor: 2.2
+ rotation_slow_down_factor: 2.0
translation_slow_down_factor: 0.5
orient_to_goal_distance: 1.0
From c9f8dbb8fa2901fc1498eced228149842202b195 Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 27 Mar 2024 07:11:41 +0000
Subject: [PATCH 20/21] Adapt ceiling cam package to camera driver
---
.../config/camera_settings_ceiling_cam.yaml | 131 +++---------------
.../launch/ceiling_cam.launch | 24 ++--
bitbots_misc/bitbots_ceiling_cam/package.xml | 5 +-
3 files changed, 30 insertions(+), 130 deletions(-)
diff --git a/bitbots_misc/bitbots_ceiling_cam/config/camera_settings_ceiling_cam.yaml b/bitbots_misc/bitbots_ceiling_cam/config/camera_settings_ceiling_cam.yaml
index 424b70819..9abff1c91 100644
--- a/bitbots_misc/bitbots_ceiling_cam/config/camera_settings_ceiling_cam.yaml
+++ b/bitbots_misc/bitbots_ceiling_cam/config/camera_settings_ceiling_cam.yaml
@@ -1,123 +1,28 @@
-/**:
+/ceiling_cam_publisher:
ros__parameters:
-
- # The tf frame under which the images were published
- camera_frame: ceiling_cam
- # The DeviceUserID of the camera. If empty, the first camera found in the
- # device list will be used
- # device_user_id: ""
+ # The tf frame under which the images were published
+ camera_frame_id: ceiling_cam
- # The CameraInfo URL (Uniform Resource Locator) where the optional intrinsic
- # camera calibration parameters are stored. This URL string will be parsed
- # from the ROS-CameraInfoManager:
- # http://docs.ros.org/api/camera_info_manager/html/classcamera__info__manager_
- # 1_1CameraInfoManager.html#details
- camera_info_url: "package://bitbots_ceiling_cam/config/camera_calibration_ceiling_cam.yaml"
-
- # The encoding of the pixels -- channel meaning, ordering, size
- # taken from the list of strings in include/sensor_msgs/image_encodings.h
- # The supported encodings are 'mono8', 'bgr8', 'rgb8', 'bayer_bggr8',
- # 'bayer_gbrg8' and 'bayer_rggb8'
- # Default values are 'mono8' and 'rgb8'
- image_encoding: "bayer_rggb8"
+ # The name of the camera (used to discover the camera). The name can be set in the pylon viewer.
+ device_user_id: ceiling_cam
- # Binning factor to get downsampled images. It refers here to any camera
- # setting which combines rectangular neighborhoods of pixels into larger
- # "super-pixels." It reduces the resolution of the output image to
- # (width / binning_x) x (height / binning_y).
- # The default values binning_x = binning_y = 0 are considered the same
- # as binning_x = binning_y = 1 (no subsampling).
- # binning_x: 4
- # binning_y: 4
-
- # The desired publisher frame rate if listening to the topics.
- # This parameter can only be set once at startup
- # Calling the GrabImages-Action can result in a higher framerate
- frame_rate: 20.0
+ # The CameraInfo URL (Uniform Resource Locator) where the optional intrinsic
+ # camera calibration parameters are stored. This URL string will be parsed
+ # from the ROS-CameraInfoManager:
+ # http://docs.ros.org/api/camera_info_manager/html/classcamera__info__manager_1_1CameraInfoManager.html#details
+ camera_info_url: "package://bitbots_ceiling_cam/config/camera_calibration_ceiling_cam.yaml"
- # Mode of camera's shutter.
- # The supported modes are "rolling", "global" and "global_reset"
- # Default value is "" (empty) means default_shutter_mode
- shutter_mode: "global"
+ # No subsampling is used for the ceiling camera
+ binning_factor_x: 1
+ binning_factor_y: 1
- ##########################################################################
- ######################## Image Intensity Settings ########################
- ##########################################################################
- # The following settings do *NOT* have to be set. Each camera has default
- # values which provide an automatic image adjustment resulting in valid
- # images
- ##########################################################################
+ # The target frame rate
+ fps: 20.0
- # The exposure time in microseconds to be set after opening the camera.
+ # The exposure time in microseconds
exposure: 8000.0
- # The target gain in percent of the maximal value the camera supports
- # For USB-Cameras, the gain is in dB, for GigE-Cameras it is given in so
- # called 'device specific units'.
- gain: 0.3
-
- # Gamma correction of pixel intensity.
- # Adjusts the brightness of the pixel values output by the camera's sensor
- # to account for a non-linearity in the human perception of brightness or
- # of the display system (such as CRT).
- gamma: 1.0
-
- # The average intensity value of the images. It depends the exposure time
- # as well as the gain setting. If 'exposure' is provided, the interface will
- # try to reach the desired brightness by only varying the gain. (What may
- # often fail, because the range of possible exposure vaules is many
- # times higher than the gain range). If 'gain' is provided, the interface will
- # try to reach the desired brightness by only varying the exposure time. If
- # gain AND exposure are given, it is not possible to reach the brightness,
- # because both are assumed to be fix.
- # brightness: 100
-
- # Only relevant, if 'brightness' is set:
- # The brightness_continuous flag controls the auto brightness function.
- # If it is set to false, the brightness will only be reached once.
- # Hence changing light conditions lead to changing brightness values.
- # If it is set to true, the given brightness will be reached continuously,
- # trying to adapt to changing light conditions. This is only possible for
- # values in the possible auto range of the pylon API which is e.g. [50 - 205]
- # for acA2500-14um and acA1920-40gm
- # brightness_continuous: true
-
- # Only relevant, if 'brightness' is set:
- # If the camera should try to reach and / or keep the brightness, hence
- # adapting to changing light conditions, at least one of the following flags
- # must be set.
- # If both are set, the interface will use the profile that tries to keep the
- # gain at minimum to reduce white noise.
- # The exposure_auto flag indicates, that the desired brightness will be
- # reached by adapting the exposure time.
- # The gain_auto flag indicates, that the desired brightness will be
- # reached by adapting the gain.
- # exposure_auto: true
- # gain_auto: true
-
- ##########################################################################
-
- # The timeout while searching the exposure which is connected to the
- # desired brightness. For slow system this has to be increased.
- # exposure_search_timeout: 5.0
-
- # The exposure search can be limited with an upper bound. This is to prevent
- # very high exposure times and resulting timeouts.
- # A typical value for this upper bound is ~2000000us.
- # auto_exposure_upper_limit: 2000000.0
-
- # The MTU size. Only used for GigE cameras.
- # To prevent lost frames configure the camera has to be configured
- # with the MTU size the network card supports. A value greater 3000
- # should be good (1500 for RaspberryPI)
- # gige:
- # gige/mtu_size: 9000
-
- # Only used for GigE cameras.
- # The inter-package delay in ticks to prevent lost frames.
- # For most of GigE-Cameras, a value of 1000 is reasonable.
- # For cameras used on a RaspberryPI this value should be set to 11772.
- # gige:
- # gige/inter_pkg_delay: 1000
+ # The target raw gain of the camera sensor (similar to ISO)
+ gain: 150
diff --git a/bitbots_misc/bitbots_ceiling_cam/launch/ceiling_cam.launch b/bitbots_misc/bitbots_ceiling_cam/launch/ceiling_cam.launch
index 1a3ef6733..de3c237db 100644
--- a/bitbots_misc/bitbots_ceiling_cam/launch/ceiling_cam.launch
+++ b/bitbots_misc/bitbots_ceiling_cam/launch/ceiling_cam.launch
@@ -3,29 +3,23 @@
-
-
-
-
-
+
+
+
+
+
+
-
-
-
-
-
-
+
-
+
-
+
-
-
diff --git a/bitbots_misc/bitbots_ceiling_cam/package.xml b/bitbots_misc/bitbots_ceiling_cam/package.xml
index cf140617e..18657f90c 100644
--- a/bitbots_misc/bitbots_ceiling_cam/package.xml
+++ b/bitbots_misc/bitbots_ceiling_cam/package.xml
@@ -7,13 +7,14 @@
Marc BestmannHamburg Bit-Bots
-
+
MITHamburg Bit-Bots
+ apriltag_ros
+ bitbots_basler_camerabitbots_docs
- pylon_ros2_camera_wrapperimage_proctf2_ros
From 67585ad122af8f4b82e564397914c21d65deefce Mon Sep 17 00:00:00 2001
From: Florian Vahl
Date: Wed, 27 Mar 2024 17:54:58 +0100
Subject: [PATCH 21/21] Update bitbots_misc/bitbots_ipm/launch/ipm.launch
Co-authored-by: Jan Gutsche <34797331+jaagut@users.noreply.github.com>
---
bitbots_misc/bitbots_ipm/launch/ipm.launch | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/bitbots_misc/bitbots_ipm/launch/ipm.launch b/bitbots_misc/bitbots_ipm/launch/ipm.launch
index a44ac382e..81b264066 100644
--- a/bitbots_misc/bitbots_ipm/launch/ipm.launch
+++ b/bitbots_misc/bitbots_ipm/launch/ipm.launch
@@ -1,9 +1,9 @@
-
-
-
+
+
+