Skip to content

Commit

Permalink
refactored .cpp files for clang-format
Browse files Browse the repository at this point in the history
  • Loading branch information
Nareshp1 committed Mar 27, 2024
1 parent 49a0620 commit 917a463
Show file tree
Hide file tree
Showing 2 changed files with 31 additions and 32 deletions.
21 changes: 10 additions & 11 deletions mil_common/gnc/odometry_utils/src/odometry_to_tf.cpp
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
#include <nav_msgs/Odometry.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/transform_datatypes.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/transform_broadcaster.h>

#include <map>
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <rclcpp/rclcpp.hpp>
#include <string>

namespace odometry_utils
{
Expand Down Expand Up @@ -49,11 +48,11 @@ class odometry_to_tf : public rclcpp::Node
virtual void onInit()
{
tf_br_ = std::make_unique<tf2_ros::TransformBroadcaster>(this);
odom_sub = this->create_subscription<nav_msgs::msg::Odometry>("odom", 10, std::bind(&OdometryToTf::handle_odom, this, std::placeholders::_1));

odom_sub = this->create_subscription<nav_msgs::msg::Odometry>(
"odom", 10, std::bind(&OdometryToTf::handle_odom, this, std::placeholders::_1));
}
};

}
#include <rclcpp_components/register_node_macro.hpp> // Include macro to register the component
RCLCPP_COMPONENTS_REGISTER_NODE(odometry_utils::OdometryToTf) // Register the node as a component
} // namespace odometry_utils
#include <rclcpp_components/register_node_macro.hpp> // Include macro to register the component
RCLCPP_COMPONENTS_REGISTER_NODE(odometry_utils::OdometryToTf) // Register the node as a component
42 changes: 21 additions & 21 deletions mil_common/gnc/odometry_utils/src/transform_odometry.cpp
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
#include <eigen_conversions/eigen_msg.h>
#include <rclcpp/node.hpp>
#include <odom_estimator/odometry.h>
#include <odom_estimator/unscented_transform.h>
#include <odom_estimator/util.h>
#include <rclcpp/rclcpp.h>
#include <tf2/transform_datatypes.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>
#include <tf2_eigen/tf2_eigen.h>
#include <nav_msgs/msg/odometry.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <nav_msgs/msg/odometry.hpp>
#include <pluginlib/class_list_macros.hpp>
#include <rclcpp/node.hpp>

namespace odometry_utils
{
Expand Down Expand Up @@ -67,24 +67,25 @@ class transform_odometry : public rclcpp::Node
tf2::fromMsg(righttransform.transform.rotation, right_q);

EasyDistributionFunction<Odom, Odom, Vec<0> > transformer(
[this, &left_p, &left_q, &right_p, &right_q](Odom const &odom, Vec<0> const &extra)
{
return Odom(odom.stamp, frame_id, child_frame_id,
left_p + left_q * (odom.pos + odom.orient * right_p),
left_q * odom.orient * right_q,
right_q.inverse() * (odom.vel - right_p.cross(odom.ang_vel)),
right_q.inverse() * odom.ang_vel);
},
GaussianDistribution<Vec<0> >(Vec<0>(), SqMat<0>()));
[this, &left_p, &left_q, &right_p, &right_q](Odom const &odom, Vec<0> const &extra)
{
return Odom(odom.stamp, frame_id, child_frame_id, left_p + left_q * (odom.pos + odom.orient * right_p),
left_q * odom.orient * right_q, right_q.inverse() * (odom.vel - right_p.cross(odom.ang_vel)),
right_q.inverse() * odom.ang_vel);
},
GaussianDistribution<Vec<0> >(Vec<0>(), SqMat<0>()));

pub.publish(msg_from_odom(transformer(odom_from_msg(*msgp))));
}

public:
transform_odometry() : Node("transform_odometry"), tf_buffer_(this->get_clock()), tf_listener_(std::make_shared<tf2_ros::TransformListener>(tf_buffer_))
transform_odometry()
: Node("transform_odometry")
, tf_buffer_(this->get_clock())
, tf_listener_(std::make_shared<tf2_ros::TransformListener>(tf_buffer_))
{
this->declare_parameter<std::string>("frame_id", "default_frame_id"); // Default value as example
this->declare_parameter<std::string>("child_frame_id", "default_child_frame_id"); // Default value as example
this->declare_parameter<std::string>("frame_id", "default_frame_id"); // Default value as example
this->declare_parameter<std::string>("child_frame_id", "default_child_frame_id"); // Default value as example

if (!this->get_parameter("frame_id", frame_id))
{
Expand All @@ -96,12 +97,11 @@ class transform_odometry : public rclcpp::Node
}

sub = this->create_subscription<nav_msgs::msg::Odometry>(
"orig_odom", 10,
std::bind(&TransformOdometry::handle, this, std::placeholders::_1));
"orig_odom", 10, std::bind(&TransformOdometry::handle, this, std::placeholders::_1));

pub = this->create_publisher<nav_msgs::msg::Odometry>("odom", 10);
};
};

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(odometry_utils::TransformOdometry)
RCLCPP_COMPONENTS_REGISTER_NODE(odometry_utils::TransformOdometry)
}

0 comments on commit 917a463

Please sign in to comment.