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 @@ - + true true @@ -3879,12 +3880,12 @@ __default_topic__ imu - imu_frame + imu_frame_uncalibrated 100.0 0.0 0 0 0 0 0 0 - imu_frame + imu_frame_uncalibrated 0 0 0 0 0 0