Closed engcang closed 6 months ago
Hi @engcang,
In general users should set the EKF origin using the ground station. E.g. open MP's Flight Data screen and right-mouse-button click on the map and select Set Home Here, Set EKF Origin Here
Alternatively we've got a Lua script here that could be modified and used.
I've created a wiki page issue here to document this better: https://github.com/ArduPilot/ardupilot_wiki/issues/5935
I'll go ahead and close this issue but I'll see replies in case you think the above isn't sufficient.
Hi @rmackay9
After I publish the SLAM's estimated pose via /mavros/vision_pose/pose, which is VISION_POSITION_ESTIMATE, mavproxy outputs
AP: EKF3 IMU0 yaw aligned
AP: EKF3 IMU1 yaw aligned
AP: EKF3 IMU0 is using external nav data
AP: EKF3 IMU0 initial pos NED = 0.0,-0.0,-0.1 (m)
AP: EKF3 IMU1 is using external nav data
AP: EKF3 IMU1 initial pos NED = 0.0,-0.0,-0.1 (m)
and also mavros which is connected to the pixhawk outputs
[ INFO] [1715073248.269162075, 82.965000000]: FCU: EKF3 IMU0 yaw aligned
[ INFO] [1715073248.269425090, 82.965000000]: FCU: EKF3 IMU1 yaw aligned
[ INFO] [1715073248.271926815, 82.968000000]: FCU: EKF3 IMU0 is using external nav data
[ INFO] [1715073248.272076282, 82.968000000]: FCU: EKF3 IMU0 initial pos NED = 0.0,-0.0,-0.1 (m)
[ INFO] [1715073248.272214568, 82.968000000]: FCU: EKF3 IMU1 is using external nav data
[ INFO] [1715073248.272355966, 82.968000000]: FCU: EKF3 IMU1 initial pos NED = 0.0,-0.0,-0.1 (m)
Hi @engcang
Perhaps I'm misunderstanding some questions so apologies if you already know some of the above.
Hope that helps.
@engcang
In Mavlink To set the EKF Origin, you need to send SET_GPS_GLOBAL_ORIGIN, in Mavros you can use global_position plugin with this topic /mavros/global_position/set_gp_origin
. The topic used geographic_msgs::GeoPointStamped message.
@rmackay9 Thank you for your detailed and fast reply. With the Lua script you attached, the drone can successfully take off in GUIDED mode without GPS/GNSS. The second question was about the order of command. I read somewhere that arming -> mode change into GUIDED cannot takeoff drone, but only mode change into GUIDED -> arming -> then drone can takeoff. Is this true information?
I was about to ask how I can set the EKF origin without Lua script but with mavros (mavlink) command, but thanks to @FahrulID I just checked it works well!
I've got an another question about landing in GUIDED mode. In PX4, with OFFBOARD mode (GUIDED in Ardupilot), the command with the z-axis downward flies the drone vertically downward and then it disarms automatically after it contacts the ground (i.e., mavros/setpoint_position/local's translation values).
So, is it same in Ardupilot? or do I have to use /mavros/cmd/land again to land the drone as we have to do for the takeoff?
Hi @engcang,
Yes, we've got a wiki page here which describes the commands to control the vehicle (in Guided mode) and includes the Takeoff command. https://ardupilot.org/dev/docs/copter-commands-in-guided-mode.html
@engcang sorry to bring this issue up again, could you please tell me your setup, as I have issue on VISION_POSITION_ESTIMATE using Realsense T265 where my LOCAL_POSITION_NED overshoot so much before going to the right position.
@FahrulID Try to set VISO_DELAY_MS higher. I use 100ms.
Hi @FahrulID,
The best way to get help is probably to post in the support forums and include an onboard log. As we say, it's all guesswork without a log. The issue could be either an estimation or a control issue.
Feature request
Hi. I have been used PX4 with Pixhawk for a long time implementing many autonomous flying drones with SLAM or VIOs (you may want to refer to the clips 1, 2, 3, etc. I recently had some chances to try Ardupilot and found it great to tune controller gains. I successfully and easily migrated my former autonomous flying algorithms and tested them with the same code except the takeoff and landing. I manually tookoff the drone and then changed the mode to GUIDED.
Sadly, I Googled as much as possible and pretty sure that takeoff in GUIDED mode without GPS/GNSS but SLAM, without manually clicking "Set home" on the MissionPlanner, without manually taking off the drone and then changing the mode to GUIDED to fly the drone autonomously, is not possible.
I kindly ask if there exists the proper way to takeoff the drone in GUIDED mode without any human actions but only codes, without GPS/GNSS but SLAM (I am using /mavros/vision_pose/pose currently).
Otherwise, I would like to ask if you have any plans to implement the functional in the near future, or why you would not.
Describe the solution you'd like
Platform [ ] All [ ] AntennaTracker [X] Copter [ ] Plane [ ] Rover [ ] Submarine