Skip to content

Commit

Permalink
make publish msg unique_ptr (#18)
Browse files Browse the repository at this point in the history
* make publish msg unique_ptr

* clang-format action fixes (#19)

Co-authored-by: makeecat <[email protected]>

---------

Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
Co-authored-by: makeecat <[email protected]>
  • Loading branch information
3 people authored Mar 1, 2024
1 parent 37f1bb9 commit df29714
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 16 deletions.
2 changes: 0 additions & 2 deletions include/transform_nodelet_ros2.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@ namespace transform_nodelet_ns
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odomimu;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odomworldB0;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odomworld;
nav_msgs::msg::Odometry::SharedPtr odomBinW;
nav_msgs::msg::Odometry::SharedPtr odomBinB0;
bool got_init_tf = false;
bool init_world_with_vicon = false;
int skip_count = 0;
Expand Down
23 changes: 9 additions & 14 deletions src/transform_nodelet_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,17 +74,16 @@ void OvtransformNodeletClass::setupTransformationMatrix(const std::string transf
RCLCPP_INFO(this->get_logger(), "T_cam_imu:");
for (int i = 0; i < 3; ++i) {
for (int j = 0; j < 4; ++j) {
T_ItoC(i,j) = T_cam_imu["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
T_ItoC(i, j) = T_cam_imu["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
RCLCPP_INFO(this->get_logger(), " r%d_c%d: %f", i, j,
T_cam_imu["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>());

}
}

RCLCPP_INFO(this->get_logger(), "T_cam_body:");
for (int i = 0; i < 3; ++i) {
for (int j = 0; j < 4; ++j) {
T_CtoB(i,j) = T_cam_body["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
T_CtoB(i, j) = T_cam_body["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
RCLCPP_INFO(this->get_logger(), " r%d_c%d: %f", i, j,
T_cam_body["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>());
}
Expand All @@ -93,7 +92,7 @@ void OvtransformNodeletClass::setupTransformationMatrix(const std::string transf
RCLCPP_INFO(this->get_logger(), "T_B0_W:");
for (int i = 0; i < 3; ++i) {
for (int j = 0; j < 4; ++j) {
T_B0toW(i,j) = T_B0_W["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
T_B0toW(i, j) = T_B0_W["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>();
RCLCPP_INFO(this->get_logger(), " r%d_c%d: %f", i, j,
T_B0_W["r" + std::to_string(i)]["c" + std::to_string(j)].as<double>());
}
Expand Down Expand Up @@ -182,14 +181,10 @@ void OvtransformNodeletClass::odomCallback(const nav_msgs::msg::Odometry::Shared
got_init_tf = true;
}

if (!odomBinW) {
odomBinW = std::make_shared<nav_msgs::msg::Odometry>();
odomBinW->header.frame_id = "world";
}
if (!odomBinB0) {
odomBinB0 = std::make_shared<nav_msgs::msg::Odometry>();
odomBinB0->header.frame_id = "odom";
}
auto odomBinW = std::make_unique<nav_msgs::msg::Odometry>();
odomBinW->header.frame_id = "world";
auto odomBinB0 = std::make_unique<nav_msgs::msg::Odometry>();
odomBinB0->header.frame_id = "odom";
odomBinW->header.stamp = odomIinM.header.stamp;
odomBinB0->header.stamp = odomIinM.header.stamp;

Expand Down Expand Up @@ -289,8 +284,8 @@ void OvtransformNodeletClass::odomCallback(const nav_msgs::msg::Odometry::Shared
// odomBinW.pose.covariance(14));
// }

pub_odomworld->publish(*odomBinW);
pub_odomworldB0->publish(*odomBinB0);
pub_odomworld->publish(std::move(odomBinW));
pub_odomworldB0->publish(std::move(odomBinB0));
}
} // namespace transform_nodelet_ns

Expand Down

0 comments on commit df29714

Please sign in to comment.