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

Doubt: How do you send state estimates to Flight controller in gazebo sim setup. #2

Open
Pallav1299 opened this issue Oct 31, 2024 · 8 comments

Comments

@Pallav1299
Copy link

Hi @klaxalk,

I just started using the gazebo-ROS simulation setup.

  1. Do you send state estimation output from Estimation manager to flight controller? If yes how? I am not able to find it in mrs_px4_hw_api?
  2. I expected that you must be using "mavros/odom/out" topic? Am I right?
  3. Do you directly send ground truth data from simulation to flight controller via mavlink?

Thanks.

@klaxalk
Copy link
Member

klaxalk commented Nov 2, 2024

Hey @Pallav1299, so far we have not got the need to send our state estimates to the flight controller, since we take care of the attitude control (and everything above that) on the ROS side. The only data data flows from us to the flight controller are currently the

  • control output
  • arming/disarming command
  • offboard on trigger

However I see that someone might need that functionality, e.g., for using a motion capture system as a "fake GPS" sources for PX4. In such special case, I would probably interface the source of data (motion capture) directly to mavros. I am not sure if an abstraction should be included in the HW Api for this...

@Pallav1299
Copy link
Author

Hey @klaxalk

Won't you suggest Flight controller failsafes(e.g. switching to secondary source on Flight controller) in case of issues with OBC(on board computer) or OBC-to-flight controller? It's suggested in the paper to use RC in such cases. Is it really scalable if we're to connect all swarm agents to an RC?

I would prefer controlled landing, when and where I want, over Flight controller internal failsafes(landing etc.), until absolutely necessary. Although, I can see that it adds flight controller firmware constraints.

What do you think about it? I'm curious to know the thought process here.

Thanks

@Pallav1299
Copy link
Author

Pallav1299 commented Nov 6, 2024

Hey @klaxalk @petrlmat, another question,

"gps_garmin" estimator uses the hw_api/position topic. From the px4_hw_api code I found that the source of hw_api/position rostopic comes from mavros_local_position_in which is remapped to mavros/local_position/odom link to launch file

  1. What's the source of this position? Is it the estimator running on the flight controller software fusing some external source (GPS etc.) with FCU IMU to give odometry via mavros to HW_API? Or, the position is being estimated only using IMU data on the flight controller software?
  2. If there's no external source(GPS etc.) fusion on flight controller estimator, how do we go about accel and gyro bias correction over time?
  3. Are you only using flight controller software to relay sensor data over MAVROS to the HW_API?

I've mostly used Ardupilot. If there's something that I'm missing from PX4's perspective, please let me know.

Thanks again.

@Pallav1299
Copy link
Author

However I see that someone might need that functionality, e.g., for using a motion capture system as a "fake GPS" sources for PX4. In such special case, I would probably interface the source of data (motion capture) directly to mavros. I am not sure if an abstraction should be included in the HW Api for this...

I tried using the simulation setup inside mrs_lio_sam_core and enabled GCS.

"Mavlink Inspector" on QGroundControl showed incoming ODOMETRY message. Is it only for simulation? Or for realworld as well?

@petrlmat
Copy link
Member

petrlmat commented Nov 7, 2024

Hey @klaxalk @petrlmat, another question,

"gps_garmin" estimator uses the hw_api/position topic. From the px4_hw_api code I found that the source of hw_api/position rostopic comes from mavros_local_position_in which is remapped to mavros/local_position/odom link to launch file

  1. What's the source of this position? Is it the estimator running on the flight controller software fusing some external source (GPS etc.) with FCU IMU to give odometry via mavros to HW_API? Or, the position is being estimated only using IMU data on the flight controller software?
  2. If there's no external source(GPS etc.) fusion on flight controller estimator, how do we go about accel and gyro bias correction over time?
  3. Are you only using flight controller software to relay sensor data over MAVROS to the HW_API?

I've mostly used Ardupilot. If there's something that I'm missing from PX4's perspective, please let me know.

Thanks again.

Hi @Pallav1299 ,

  1. The position from px4 is the position estimated by the px4 EKF estimator. Estimating the position using IMU data only would cause too large of a drift.
  2. If we are using other source of localization, then the bias estimation is not handled by PX4 but by some VIO or LIO algorithm.
  3. We also use it to control the drone by attitude rate commands, calibration, control using RC, etc.

@petrlmat
Copy link
Member

petrlmat commented Nov 7, 2024

However I see that someone might need that functionality, e.g., for using a motion capture system as a "fake GPS" sources for PX4. In such special case, I would probably interface the source of data (motion capture) directly to mavros. I am not sure if an abstraction should be included in the HW Api for this...

I tried using the simulation setup inside mrs_lio_sam_core and enabled GCS.

"Mavlink Inspector" on QGroundControl showed incoming ODOMETRY message. Is it only for simulation? Or for realworld as well?

Not sure what odometry message are you referring to or what data are you expecting to be in it, but PX4 estimation runs even when we use external localization (e.g. LIOSAM), so it will be outputting some data regardless on the localization modality. LIOSAM was so far used only in simulation and on rosbags from real flights by us. There were some bugs in it that prevented real-time usage. I think the bugs should be fixed by now but testing it wasn't a priority for us as we are now satisfied with the performance of ALOAM, which we use for LiDAR-based flights.

@Pallav1299
Copy link
Author

Pallav1299 commented Nov 8, 2024

Hey @petrlmat, thanks for your prompt responses.
I recently noticed the Discussions section. Hope you don't mind continuing this discussion here.

  1. The position from px4 is the position estimated by the px4 EKF estimator. Estimating the position using IMU data only would cause too large of a drift.

I couldn't find clear references to this in these papers 1 2.

  1. It's still a little ambiguous to me. Which sensor data is fed to the PX4 EKF estimator? I haven't been able to find its references. Do you have any references to share which might help here.
  2. If it's GPS, what if GPS goes bad or in GPS denied scenarios? What happens to the PX4 estimator? Does it go into failsafe?
  3. Would you suggest fusing external navigation source data(ALOAM, LIOSAM, VIO) into the PX4 EKF estimator in general? What about critical cases(like gps denied)?

2. If we are using other source of localization, then the bias estimation is not handled by PX4 but by some VIO or LIO algorithm.

  1. Trying to get it right. Do you mean VIO/LIO should have bias estimation OR the mrs_state_Estimator's LKF takes care of it?
  2. Do you mean VIO/LIO estimates are fused with PX4/Ardupilot EKF?
  3. 2 mentions this:
    While the IMU of the onboard autopilot provides the orientation R, the heading **η** is prone to drift due to the bias of the gyroscopes in Micro-Electromechanical Systems (MEMS) IMUs. We correct this drift in a standalone heading filter, which fuses Ṙ gyro measurements with A-LOAM η corrections
    This takes care of the heading bias but the what about the other gyro bias components(roll, pitch) in PX4 EKF state?

I'm yet to read the papers to depth. But if you could clarify these, it would be quite helpful.

Thanks again

@tejalbarnwal
Copy link

Hi @petrlmat and @klaxalk , I’m particularly concerned about some of the above questions as well. I’m working on an indoor inspection task where GPS isn't available. I’m transitioning to the MRS system and have some concerns regarding its integration:

Current Setup:
I use VIO with an external IMU and camera on the onboard computer (OBC). The VIO output is sent to the Pixhawk, where its EKF fuses this with onboard IMU data to estimate the drone's state.

MRS Transition:
The MRS estimator manager uses attitude and body rates from Pixhawk (via odometry) and fuses them with other localization sources on the OBC to estimate position, velocity, acceleration, and heading.

Concerns:
Roll and Pitch:
Why are roll and pitch not estimated by the MRS system?

Autopilot Modes:
Modes like Hold and Manual Position depend on the Pixhawk estimator having accurate position and velocity. If fusion happens only on the OBC without sending state estimates back to Pixhawk, these modes won’t function correctly.

Feedback Loop:
I was considering feeding the MRS estimator’s results (position, velocity) back to the Pixhawk to allow it to fuse this information with its onboard IMU data. This would ensure the Pixhawk has accurate estimates for modes like Hold or Manual Position. However, this feels like a “chicken-and-egg” problem, where the Pixhawk provides IMU data(attitude and attitude rates via MAVROS odom) to the onboard computer, which then processes it and sends back state estimates to the Pixhawk.

Would you have any guidance on how to handle this situation effectively while ensuring that the autopilot modes remain functional?

Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants