VISION_POSITION_ESTIMATE not appearing in QGroundControl

If you use Windows it could be a driver problems, try to uninstall and reinstall the usb driver that comes with MP (or the entire MP).

Thanks for the tip, I’m using a Linux computer and it’s working well with ChibiOS !
I have now the v3.6.6, with the VISO parameter, which is set. But still, the problem of desired pose remains…
No pain, no gain, right ? :stuck_out_tongue:

Ok, I have found where it does come from. After a long analysis and debug on the ArduCopter code, it seems that in the file “mode_guided.cpp”, the function “pos_control_run()” is called at 100Hz without problem.
But in the first condition of this function :

The variable ap.land_complete is TRUE (and suppose to be false to go through). For testing, I deleted this variable, and now the pose desired is set.
So it is solved !

Hello, Kilo.
I think I have encountered the same problem as you and really want to know about your solutions.
My environment:

  1. ubuntu16.04, ROS Kinetic and ArduPilot 3.6.7.
  2. AHRS_EKF_TYPE 2
    EKF2_ENABLE 1
    EKF3_ENABLE 0
    EK2_GPS_TYPE 3
    GPS_TYPE 0
    COMPASS_USE 0
    VISO_TYPE 0
  3. mode GUIDED

I have checked the apm_pluginlists.yaml and the apm.launch
And I use
sim_vehicle.py —map —console —out udp:127.0.0.1:14551
to sim the copter
use
rosrun macros apm.launch fcu_url:=udp://127.0.0.1:14551@
to launch mavros

The GPS_GLOBAL_ORIGIN & HOME_POSITION was set(checked in QGC)

I echoed the topic /mavros/vision_pose/pose and it did publish
But I could see nothing when I echoed the topic /mavros/local_position/pose, not to mention to get the VISION_ESTIMATE_POSITION in QGC.
I was wondering If you have any ideas.
Need more details, pls let me know.

————————————————————
I suppose the problem should be No 3D Fix
I don’t know if I’m doing those commands in a right order:
I’m pretty sure that I fed the ROS with /mavros/vision_pose/pose before I start the sim_vehicle.py and it’s running all the time. After that, I launched the apm.launch and set the gps_position & home_position. But when I switch to mode GUIDEDand tend to arm, there came with the ERR No 3D fix.
I checked the rqt_graph, it’s strange that mavros didn’t subscribe the vision topic but the tf topic from the SLAM part.

Hello @IrisGreen,
Indeed it seems that you are doing all right.
When you send GPS_GLOBAL_ORIGIN & HOME_POSITION, are you sending a coherent position (like the position of your city) and not just a random pose ?
For my simulation, I run ArduPilot (sim_vehicle & apm.launch) before feeding mavros/vision_pose/pose without any issue. So I don’t think this is a running order problem.

Thanks for your kind reply. But it didn’t work out well.The problem should be something else and I have to take a deeper look. I’ll keep trying anyway. If I had figure it out, I will give a response: )

Hi i am a noob that needs your help . I am working on external position using pozyx. my goal is to feed the drone with external position coming from the pozyx tag through the topic /mavros/mocap/pose . I have the following parameter on my Quad :
AHRS_EKF_TYPE 2
EKF2_ENABLE 1
EKF3_ENABLE 0
GPS_TYPE 0
EK2_GPS_TYPE 3
COMPASS_USE 0
VISO_TYPE 0
BCN_TYPE 1(Meanning pozyx)
BCN_ORIENT_YAW 0
ARMING_CHECK 0
On the Quad there is a RPI 3 model B V1.2 connected to a pozyx tag
I followed the tutuorial to place the 4 anchors of the pozyx following the N pattern to place the anchors .
Pozyx is using ENU and ROS is supposed to convert the data from ENU to NED from what i read.
Although i aligned the North with the x-axis of my mocap system . when i listen to the /mavros/local_position/pose , only the z converge to the external data . x_local and y_local have no correlation from the published data


like we can see on the above picture , the local position are on the left pic and the mocap are on the right .
Of course before listeing to the local_position/pose data,i send the mocap , then i set the gps_global_origin and the home position
How can i do to so that external positions and local position match ?
What do i miss ? , Any help will be welcome

HI @Joel_Fankam I would like to know something about your system to better understand.
Which kind of data do you get from your mocap system?
In which way, from this data, you form a message to send to /mavros/mocap/pose topic?

Anyway it could be a problem of reference frames and transformations between them.
@LuckyBird explains very well the key concept to send the right messages with the right transformation for reference frame in his github repo and in his blog posts:

HI @anbello, I am getting x,y,z , i can also get the quaternion from the pozyx system(ENU). The pozyx tag communicate with 4 others anchors and give me x,y,z coordinates
then i send then i publish them with PoseStamped trough the /mavros/mocap/pose. i dd not change nothing since ROS is supposed to convert data to NED . i will read the tips you gave me and let you know

Please show the ATT_POS_MOCAP message you receive from GCS , if you are using Mission Planner do CTRL-F and select Mavlink Inspector.

From you example above it seems you do not send the quaternions , please make sure that you map the pose topic correctly as described here:
https://dev.px4.io/master/en/ros/external_position_estimation.html#relaying_pose_data_to_px4

@chobitsfan could give you some guidance on this.

that is what i am getting


Do i have to use VISION_POSE_ESTIMATE
I think one of my big problem is with the frame coordinates system .
I manage to get quaternion from the pozyx tag . i get qx=0,5 qy=0,5 qz=0,5 qw=0,5

I dont see the vision signal , like I wrote before,

ArduPilot can process both Quaternions and Euler Angles, but just make sure that Mavros read Pozyx and output the correct signal to MavLink.

I am working with EKF2, and on the link you send me :
https://dev.px4.io/master/en/ros/external_position_estimation.html#relaying_pose_data_to_px4
Only vision pipeline is allowed
that means i have to remap the pose topic i get from the pozyx to the /mavros/vision/pose?
because i was sending pose to /mavros/mocap/pose

I suspect the wiki is outdated, just to make sure you can ask @vooon for confirmation/guidance on the Mavros Channel

Now i understand the Frame Transformation issues . But i still have some questions
I can get the position as well as the quaternion from the pozyx’s tag
my issues is about how to get the name of the origin of the world frame of the pozyx , and the name of the frame of the pozyx’s tag , because while i am sending mocap_data i also set header.frame_id=“pozyx”,
should i use it to send the transformation frame ?
Another question is that should i send the mocap/pose and send the transform to the /tf or only send the frame transformation ?

Hi Monsieur ppoirier . I read a lot about the transformation data and i found that i do not need to transform my data since i am able to get the position as well as the quaternion(transalation and rotation according to my world origin). I still face the same issues about my x, and y coordinates . Can i try to send the data i receive to mavros/vision_pose/pose ?

Hello Joel
If you you use quaternions, You could work with mocap pose messages because vision is using Euler angles

Hi you are right , but in the px4 tutorial

If you’re working with EKF2, only the “vision” pipelines are supported. To use MoCap data with EKF2 you will have to remap the pose topic that you get from MoCap:

  • MoCap ROS topics of type geometry_msgs/PoseStamped or geometry_msgs/PoseWithCovarianceStamped must be remapped to /mavros/vision_pose/pose . The geometry_msgs/PoseStamped topic is most common as MoCap doesn’t usually have associated covariances to the data.
  • If you get data through a nav_msgs/Odometry ROS message then you will need to remap it to /mavros/odometry/odom .

that is what is said about the mocap pipeline. I don’t know ob it is also relevant for Ardupilot ?

hi , it is also possible to use quaternion with vision message since it is needed to use PoseStamped object . I tried it but i got the same undesired result .
I have another question Monsieur ppoirier . since the north position get by the autopilot is not static ,
When i get the north direction with 0 degree after some time , i have to adjust the drone again to head to the north . I also tried to align my positioning system with the x axis heading the north direction . but i dint have any instrument to have an accurate direction .
In the case that the pozyx system and the x axis of the drone are not perfectly aligned to the north direction , is that still possible to perform external navigation data with a certain accuracy ?
thanks

If you experience problems related to compass, if you build from master you can disable compass, otherwise I cannot really help because I don’t use Pozyx.

@chobitsfan might