From 302bae51c675a6ac004db9a81b03228effaeb168 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Wed, 3 Jul 2024 16:26:14 +0900 Subject: [PATCH] Enable Eagleye to convert septentrio_gnss_driver/PVTGeodetic messages for velocity source Signed-off-by: TaikiYamada4 --- eagleye_rt/config/README.md | 2 +- eagleye_rt/config/eagleye_config.yaml | 2 +- eagleye_util/gnss_converter/package.xml | 3 ++ .../src/gnss_converter_node.cpp | 37 +++++++++++++++++++ 4 files changed, 42 insertions(+), 2 deletions(-) diff --git a/eagleye_rt/config/README.md b/eagleye_rt/config/README.md index f1de4f5e..7505a637 100644 --- a/eagleye_rt/config/README.md +++ b/eagleye_rt/config/README.md @@ -17,7 +17,7 @@ The parameters for estimation in Eagleye can be set in the `config/eagleye_confi | imu_topic | string | Topic name to be subscribed to in node (sensor_msgs/Imu.msg) | /imu/data_raw | | twist.twist_type | int | Topic type to be subscribed to in node (TwistStamped : 0, TwistWithCovarianceStamped: 1) | 0 | | twist.twist_topic | string | Topic name to be subscribed to in node | /can_twist | -| gnss.velocity_source_type | int | Topic type to be subscribed to in node (rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3) | 0 | +| gnss.velocity_source_type | int | Topic type to be subscribed to in node (rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3, septentrio_gnss_driver/PVTGeodetic: 4) | 0 | | gnss.velocity_source_topic | string | Topic name to be subscribed to in node | /rtklib_nav | | gnss.llh_source_type | int | Topic type to be subscribed to in node (rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2) | 0 | | gnss.llh_source_topic | string | Topic name to be subscribed to in node | /rtklib_nav | diff --git a/eagleye_rt/config/eagleye_config.yaml b/eagleye_rt/config/eagleye_config.yaml index 92e9f6c4..67375604 100644 --- a/eagleye_rt/config/eagleye_config.yaml +++ b/eagleye_rt/config/eagleye_config.yaml @@ -10,7 +10,7 @@ twist_topic: /can_twist imu_topic: /imu/data_raw gnss: - velocity_source_type: 0 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3 + velocity_source_type: 0 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3, septentrio_gnss_driver/PVTGeodetic: 4 velocity_source_topic: /rtklib_nav llh_source_type: 0 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2 llh_source_topic: /rtklib_nav diff --git a/eagleye_util/gnss_converter/package.xml b/eagleye_util/gnss_converter/package.xml index 82374cc4..90664e12 100644 --- a/eagleye_util/gnss_converter/package.xml +++ b/eagleye_util/gnss_converter/package.xml @@ -13,6 +13,7 @@ sensor_msgs nmea_msgs ublox_msgs + septentrio_gnss_driver rtklib_msgs eagleye_coordinate eagleye_navigation @@ -22,6 +23,7 @@ sensor_msgs nmea_msgs ublox_msgs + septentrio_gnss_driver rtklib_msgs eagleye_coordinate eagleye_navigation @@ -31,6 +33,7 @@ sensor_msgs nmea_msgs ublox_msgs + septentrio_gnss_driver rtklib_msgs eagleye_coordinate eagleye_navigation diff --git a/eagleye_util/gnss_converter/src/gnss_converter_node.cpp b/eagleye_util/gnss_converter/src/gnss_converter_node.cpp index 3b0074fa..d6648e07 100644 --- a/eagleye_util/gnss_converter/src/gnss_converter_node.cpp +++ b/eagleye_util/gnss_converter/src/gnss_converter_node.cpp @@ -2,6 +2,7 @@ #include "rclcpp/rclcpp.hpp" #include "gnss_converter/nmea2fix.hpp" #include +#include #include #include "eagleye_coordinate/eagleye_coordinate.hpp" #include "eagleye_navigation/eagleye_navigation.hpp" @@ -82,6 +83,36 @@ void navpvt_callback(const ublox_msgs::msg::NavPVT::ConstSharedPtr msg) rtklib_nav_pub->publish(r); } +void pvtgeodetic_callback(const septentrio_gnss_driver::msg::PVTGeodetic::ConstSharedPtr msg) +{ + rtklib_msgs::msg::RtklibNav r; + r.header.frame_id = "gps"; + r.header.stamp = msg->header.stamp; + if (nav_msg_ptr != nullptr) + r.status = *nav_msg_ptr; + r.tow = msg->block_header.tow; + + double llh[3]; + llh[0] = msg->latitude; + llh[1] = msg->longitude; + llh[2] = msg->height; + double ecef_pos[3]; + llh2xyz(llh, ecef_pos); + + double enu_vel[3] = {msg->ve, msg->vn, msg->vu}; + double ecef_vel[3]; + enu2xyz_vel(enu_vel, ecef_pos, ecef_vel); + + r.ecef_pos.x = ecef_pos[0]; + r.ecef_pos.y = ecef_pos[1]; + r.ecef_pos.z = ecef_pos[2]; + r.ecef_vel.x = ecef_vel[0]; + r.ecef_vel.y = ecef_vel[1]; + r.ecef_vel.z = ecef_vel[2]; + + rtklib_nav_pub->publish(r); +} + void gnss_velocity_callback(const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr msg) { if (nav_msg_ptr == nullptr) return; @@ -127,6 +158,7 @@ int main(int argc, char** argv) rclcpp::Subscription::SharedPtr nmea_sentence_sub; rclcpp::Subscription::SharedPtr navpvt_sub; rclcpp::Subscription::SharedPtr gnss_velocity_sub; + rclcpp::Subscription::SharedPtr pvtgeodetic_sub; rclcpp::Subscription::SharedPtr navsatfix_sub; node->declare_parameter("gnss.velocity_source_type",velocity_source_type); @@ -160,6 +192,11 @@ int main(int argc, char** argv) gnss_velocity_sub = node->create_subscription( velocity_source_topic, 1000, gnss_velocity_callback); } + else if(velocity_source_type == 4) + { + pvtgeodetic_sub = node->create_subscription( + velocity_source_topic, 1000, pvtgeodetic_callback); + } else { RCLCPP_ERROR(node->get_logger(),"Invalid velocity_source_type");