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

Try running eagleye with llh_source_type=sensor_msgs/NavSatFix ( without RTKLIB and nmea_msgs::sentence topics) #332

Open
mamadouDembele opened this issue May 14, 2024 · 1 comment
Labels
question Further information is requested

Comments

@mamadouDembele
Copy link

mamadouDembele commented May 14, 2024

Hi,

I'm trying to get eagleye (develop-ros2 branch) to work with my bags, which contain the following data:

  • /can_twist (vehicle speed from can)
  • /gnss_rear/nmea_sentence (only rmc sentence data is available in the topic)
  • /gnss_front/navsatfix (sensor_msgs/NavSatFix)
  • /gnss_rear/navsatfix (sensor_msgs/NavSatFix)
  • /imu_data

My configuration file looks like this (And use_multi_antenna_mode is set to true)

/**: #GNSS cycle 5Hz, IMU cycle 50Hz.
ros__parameters:
# Estimate mode
use_gnss_mode: NMEA
use_can_less_mode: false

# Topic
twist:
  twist_type: 0 # TwistStamped : 0, TwistWithCovarianceStamped: 1
  twist_topic: /can_twist
imu_topic: /.../imu
gnss:
  velocity_source_type: 1 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
  velocity_source_topic: /.../gnss_rear/nmea_sentence
  llh_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
  llh_source_topic:  /.../gnss_rear/navsatfix

sub_gnss:
  llh_source_type: 2 # nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
  llh_source_topic:  /.../gnss_front/navsatfix

The terminal show me that:
Screenshot from 2024-05-14 14-51-30

Eagleye can't estimate the final pose
It seems eagleye doesn't use the latLonAlt info from sensor_msgs/Navsatfix for estimating the position (x, y, z).

I tried looking at the code to understand the problem. The function position_estimate can only be used for rtklib_msgs and nmea_msgs formats and not for sensor_msgs. If I'm right, that means we can use eagleye with sensor_msgs/NavSatFix. I hope my wrong.

void **position_estimate**(const rtklib_msgs::msg::RtklibNav, const geometry_msgs::msg::TwistStamped, const
eagleye_msgs::msg::StatusStamped, const eagleye_msgs::msg::Distance, const eagleye_msgs::msg::Heading, const geometry_msgs::msg::Vector3Stamped, const PositionParameter, PositionStatus*, eagleye_msgs::msg::Position*);

void **position_estimate**(const nmea_msgs::msg::Gpgga, const geometry_msgs::msg::TwistStamped, const eagleye_msgs::msg::StatusStamped, const eagleye_msgs::msg::Distance, const eagleye_msgs::msg::Heading, const geometry_msgs::msg::Vector3Stamped, const PositionParameter, PositionStatus*, eagleye_msgs::msg::Position*); 

Kind regards
Please let me know if you want my bag and the modifs I did from eagleye.

@rsasaki0109
Copy link
Collaborator

Sorry, there might be a bug with the combination of velocity_source as nmea_sentence and llh_source as nav_sat_fix. Does nmea_sentence include GGA? If it does, you should specify nmea_sentence for llh_source.

@rsasaki0109 rsasaki0109 added the question Further information is requested label May 27, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants