Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(gyro_odometer): componentize node in gyro_odometer #7090

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 7 additions & 7 deletions localization/gyro_odometer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,12 @@ project(gyro_odometer)
find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_executable(${PROJECT_NAME}
src/gyro_odometer_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/gyro_odometer_core.cpp
)

target_link_libraries(${PROJECT_NAME} fmt)

ament_auto_add_library(gyro_odometer_node SHARED
src/gyro_odometer_core.cpp
)

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_gyro_odometer
test/test_main.cpp
Expand All @@ -25,10 +20,15 @@ if(BUILD_TESTING)
rclcpp
)
target_link_libraries(test_gyro_odometer
gyro_odometer_node
${PROJECT_NAME}
)
endif()

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::gyro_odometer::GyroOdometerNode"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)

ament_auto_package(INSTALL_TO_SHARE
launch
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,17 @@
#include <memory>
#include <string>

class GyroOdometer : public rclcpp::Node
namespace autoware::gyro_odometer
{

class GyroOdometerNode : public rclcpp::Node
{
private:
using COV_IDX = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX;

public:
explicit GyroOdometer(const rclcpp::NodeOptions & options);
~GyroOdometer();
explicit GyroOdometerNode(const rclcpp::NodeOptions & node_options);
~GyroOdometerNode();

private:
void callbackVehicleTwist(
Expand Down Expand Up @@ -75,4 +78,6 @@ class GyroOdometer : public rclcpp::Node
std::deque<sensor_msgs::msg::Imu> gyro_queue_;
};

} // namespace autoware::gyro_odometer

#endif // GYRO_ODOMETER__GYRO_ODOMETER_CORE_HPP_
2 changes: 1 addition & 1 deletion localization/gyro_odometer/launch/gyro_odometer.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@

<arg name="config_file" default="$(find-pkg-share gyro_odometer)/config/gyro_odometer.param.yaml"/>

<node pkg="gyro_odometer" exec="gyro_odometer" name="gyro_odometer" output="screen">
<node pkg="gyro_odometer" exec="gyro_odometer_node" output="both">
<remap from="vehicle/twist_with_covariance" to="$(var input_vehicle_twist_with_covariance_topic)"/>

<remap from="imu" to="$(var input_imu_topic)"/>
Expand Down
5 changes: 2 additions & 3 deletions localization/gyro_odometer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,13 @@

<depend>fmt</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_autoware_utils</depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
81 changes: 46 additions & 35 deletions localization/gyro_odometer/src/gyro_odometer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "gyro_odometer/gyro_odometer_core.hpp"

#include <rclcpp/rclcpp.hpp>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
Expand All @@ -25,6 +27,42 @@
#include <memory>
#include <string>

namespace autoware::gyro_odometer
{

GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options)
: Node("gyro_odometer", node_options),
output_frame_(declare_parameter<std::string>("output_frame")),
message_timeout_sec_(declare_parameter<double>("message_timeout_sec")),
vehicle_twist_arrived_(false),
imu_arrived_(false)
{
transform_listener_ = std::make_shared<tier4_autoware_utils::TransformListener>(this);
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);

vehicle_twist_sub_ = create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"vehicle/twist_with_covariance", rclcpp::QoS{100},
std::bind(&GyroOdometerNode::callbackVehicleTwist, this, std::placeholders::_1));

imu_sub_ = create_subscription<sensor_msgs::msg::Imu>(
"imu", rclcpp::QoS{100},
std::bind(&GyroOdometerNode::callbackImu, this, std::placeholders::_1));

twist_raw_pub_ = create_publisher<geometry_msgs::msg::TwistStamped>("twist_raw", rclcpp::QoS{10});
twist_with_covariance_raw_pub_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
"twist_with_covariance_raw", rclcpp::QoS{10});

twist_pub_ = create_publisher<geometry_msgs::msg::TwistStamped>("twist", rclcpp::QoS{10});
twist_with_covariance_pub_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
"twist_with_covariance", rclcpp::QoS{10});

// TODO(YamatoAndo) createTimer
}

GyroOdometerNode::~GyroOdometerNode()
{
}

std::array<double, 9> transformCovariance(const std::array<double, 9> & cov)
{
using COV_IDX = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX;
Expand Down Expand Up @@ -100,39 +138,7 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer(
return twist_with_cov;
}

GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options)
: Node("gyro_odometer", options),
output_frame_(declare_parameter<std::string>("output_frame")),
message_timeout_sec_(declare_parameter<double>("message_timeout_sec")),
vehicle_twist_arrived_(false),
imu_arrived_(false)
{
transform_listener_ = std::make_shared<tier4_autoware_utils::TransformListener>(this);
logger_configure_ = std::make_unique<tier4_autoware_utils::LoggerLevelConfigure>(this);

vehicle_twist_sub_ = create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
"vehicle/twist_with_covariance", rclcpp::QoS{100},
std::bind(&GyroOdometer::callbackVehicleTwist, this, std::placeholders::_1));

imu_sub_ = create_subscription<sensor_msgs::msg::Imu>(
"imu", rclcpp::QoS{100}, std::bind(&GyroOdometer::callbackImu, this, std::placeholders::_1));

twist_raw_pub_ = create_publisher<geometry_msgs::msg::TwistStamped>("twist_raw", rclcpp::QoS{10});
twist_with_covariance_raw_pub_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
"twist_with_covariance_raw", rclcpp::QoS{10});

twist_pub_ = create_publisher<geometry_msgs::msg::TwistStamped>("twist", rclcpp::QoS{10});
twist_with_covariance_pub_ = create_publisher<geometry_msgs::msg::TwistWithCovarianceStamped>(
"twist_with_covariance", rclcpp::QoS{10});

// TODO(YamatoAndo) createTimer
}

GyroOdometer::~GyroOdometer()
{
}

void GyroOdometer::callbackVehicleTwist(
void GyroOdometerNode::callbackVehicleTwist(
const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_ptr)
{
vehicle_twist_arrived_ = true;
Expand Down Expand Up @@ -173,7 +179,7 @@ void GyroOdometer::callbackVehicleTwist(
gyro_queue_.clear();
}

void GyroOdometer::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr)
void GyroOdometerNode::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr)
{
imu_arrived_ = true;
if (!vehicle_twist_arrived_) {
Expand Down Expand Up @@ -241,7 +247,7 @@ void GyroOdometer::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_m
gyro_queue_.clear();
}

void GyroOdometer::publishData(
void GyroOdometerNode::publishData(
const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw)
{
geometry_msgs::msg::TwistStamped twist_raw;
Expand Down Expand Up @@ -269,3 +275,8 @@ void GyroOdometer::publishData(
twist_pub_->publish(twist);
twist_with_covariance_pub_->publish(twist_with_covariance);
}

} // namespace autoware::gyro_odometer

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::gyro_odometer::GyroOdometerNode)
30 changes: 0 additions & 30 deletions localization/gyro_odometer/src/gyro_odometer_node.cpp

This file was deleted.

6 changes: 4 additions & 2 deletions localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,8 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity)
expected_output_twist.twist.twist.angular.y = input_imu.angular_velocity.y;
expected_output_twist.twist.twist.angular.z = input_imu.angular_velocity.z;

auto gyro_odometer_node = std::make_shared<GyroOdometer>(getNodeOptionsWithDefaultParams());
auto gyro_odometer_node =
std::make_shared<autoware::gyro_odometer::GyroOdometerNode>(getNodeOptionsWithDefaultParams());
auto imu_generator = std::make_shared<ImuGenerator>();
auto velocity_generator = std::make_shared<VelocityGenerator>();
auto gyro_odometer_validator_node = std::make_shared<GyroOdometerValidator>();
Expand All @@ -135,7 +136,8 @@ TEST(GyroOdometer, TestGyroOdometerImuOnly)
{
Imu input_imu = generateSampleImu();

auto gyro_odometer_node = std::make_shared<GyroOdometer>(getNodeOptionsWithDefaultParams());
auto gyro_odometer_node =
std::make_shared<autoware::gyro_odometer::GyroOdometerNode>(getNodeOptionsWithDefaultParams());
auto imu_generator = std::make_shared<ImuGenerator>();
auto gyro_odometer_validator_node = std::make_shared<GyroOdometerValidator>();

Expand Down
Loading