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

[autoware-main] feat(gnss_converter): enable to read septentrio_gnss_driver/PVTGeodetic for velocity source #334

Merged
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
2 changes: 1 addition & 1 deletion eagleye_rt/config/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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 |
Expand Down
2 changes: 1 addition & 1 deletion eagleye_rt/config/eagleye_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 3 additions & 0 deletions eagleye_util/gnss_converter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>nmea_msgs</build_depend>
<build_depend>ublox_msgs</build_depend>
<build_depend>septentrio_gnss_driver</build_depend>
<build_depend>rtklib_msgs</build_depend>
<build_depend>eagleye_coordinate</build_depend>
<build_depend>eagleye_navigation</build_depend>
Expand All @@ -22,6 +23,7 @@
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>nmea_msgs</build_export_depend>
<build_export_depend>ublox_msgs</build_export_depend>
<build_export_depend>septentrio_gnss_driver</build_export_depend>
<build_export_depend>rtklib_msgs</build_export_depend>
<build_export_depend>eagleye_coordinate</build_export_depend>
<build_export_depend>eagleye_navigation</build_export_depend>
Expand All @@ -31,6 +33,7 @@
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>nmea_msgs</exec_depend>
<exec_depend>ublox_msgs</exec_depend>
<exec_depend>septentrio_gnss_driver</exec_depend>
<exec_depend>rtklib_msgs</exec_depend>
<exec_depend>eagleye_coordinate</exec_depend>
<exec_depend>eagleye_navigation</exec_depend>
Expand Down
37 changes: 37 additions & 0 deletions eagleye_util/gnss_converter/src/gnss_converter_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
#include "rclcpp/rclcpp.hpp"
#include "gnss_converter/nmea2fix.hpp"
#include <ublox_msgs/msg/nav_pvt.hpp>
#include <septentrio_gnss_driver/msg/pvt_geodetic.hpp>
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
#include "eagleye_coordinate/eagleye_coordinate.hpp"
#include "eagleye_navigation/eagleye_navigation.hpp"
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -127,6 +158,7 @@ int main(int argc, char** argv)
rclcpp::Subscription<nmea_msgs::msg::Sentence>::SharedPtr nmea_sentence_sub;
rclcpp::Subscription<ublox_msgs::msg::NavPVT>::SharedPtr navpvt_sub;
rclcpp::Subscription<geometry_msgs::msg::TwistWithCovarianceStamped>::SharedPtr gnss_velocity_sub;
rclcpp::Subscription<septentrio_gnss_driver::msg::PVTGeodetic>::SharedPtr pvtgeodetic_sub;
rclcpp::Subscription<sensor_msgs::msg::NavSatFix>::SharedPtr navsatfix_sub;

node->declare_parameter("gnss.velocity_source_type",velocity_source_type);
Expand Down Expand Up @@ -160,6 +192,11 @@ int main(int argc, char** argv)
gnss_velocity_sub = node->create_subscription<geometry_msgs::msg::TwistWithCovarianceStamped>(
velocity_source_topic, 1000, gnss_velocity_callback);
}
else if(velocity_source_type == 4)
{
pvtgeodetic_sub = node->create_subscription<septentrio_gnss_driver::msg::PVTGeodetic>(
velocity_source_topic, 1000, pvtgeodetic_callback);
}
else
{
RCLCPP_ERROR(node->get_logger(),"Invalid velocity_source_type");
Expand Down