Skip to content

Commit

Permalink
refactor based on linter
Browse files Browse the repository at this point in the history
Signed-off-by: a-maumau <[email protected]>
  • Loading branch information
a-maumau committed Jun 6, 2024
1 parent dd3a7a8 commit cec39af
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
6 changes: 3 additions & 3 deletions localization/twist2accel/include/twist2accel/twist2accel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,9 +63,9 @@ class Twist2Accel : public rclcpp::Node
/**
* @brief set odometry measurement
*/
void callbackTwistWithCovariance(
void callback_twist_with_covariance(
const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg);
void callbackOdometry(const nav_msgs::msg::Odometry::SharedPtr msg);
void estimateAccel(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
void callback_odometry(const nav_msgs::msg::Odometry::SharedPtr msg);
void estimate_accel(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
};
#endif // TWIST2ACCEL__TWIST2ACCEL_HPP_
14 changes: 7 additions & 7 deletions localization/twist2accel/src/twist2accel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@ Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("twist2accel", node_options)
{
sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
"input/odom", 1, std::bind(&Twist2Accel::callbackOdometry, this, _1));
"input/odom", 1, std::bind(&Twist2Accel::callback_odometry, this, _1));
sub_twist_ = create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"input/twist", 1, std::bind(&Twist2Accel::callbackTwistWithCovariance, this, _1));
"input/twist", 1, std::bind(&Twist2Accel::callback_twist_with_covariance, this, _1));

pub_accel_ = create_publisher<geometry_msgs::msg::AccelWithCovarianceStamped>("output/accel", 1);

Expand All @@ -46,28 +46,28 @@ Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options)
lpf_aaz_ptr_ = std::make_shared<LowpassFilter1d>(accel_lowpass_gain_);
}

void Twist2Accel::callbackOdometry(const nav_msgs::msg::Odometry::SharedPtr msg)
void Twist2Accel::callback_odometry(const nav_msgs::msg::Odometry::SharedPtr msg)
{
if (!use_odom_) return;

geometry_msgs::msg::TwistStamped twist;
twist.header = msg->header;
twist.twist = msg->twist.twist;
estimateAccel(std::make_shared<geometry_msgs::msg::TwistStamped>(twist));
estimate_accel(std::make_shared<geometry_msgs::msg::TwistStamped>(twist));
}

void Twist2Accel::callbackTwistWithCovariance(
void Twist2Accel::callback_twist_with_covariance(
const geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg)
{
if (use_odom_) return;

geometry_msgs::msg::TwistStamped twist;
twist.header = msg->header;
twist.twist = msg->twist.twist;
estimateAccel(std::make_shared<geometry_msgs::msg::TwistStamped>(twist));
estimate_accel(std::make_shared<geometry_msgs::msg::TwistStamped>(twist));
}

void Twist2Accel::estimateAccel(const geometry_msgs::msg::TwistStamped::SharedPtr msg)
void Twist2Accel::estimate_accel(const geometry_msgs::msg::TwistStamped::SharedPtr msg)
{
geometry_msgs::msg::AccelWithCovarianceStamped accel_msg;
accel_msg.header = msg->header;
Expand Down

0 comments on commit cec39af

Please sign in to comment.