Raw setpoint problem with px4 v1.9.0+

MOTIVATION

We have been using px4 v1.8.2 and mavros v0.31.0 for a while now.

The SITL has worked very well for us, and usually real flight tests have been good too.

But recently (past 6 months), we’ve experienced a lot of frustrating pre-flight failures during real flight tests.

After analysis of many px4 ulogs and ekf2_main.cpp, PreFlightChecker.cpp, it seems that large magnetometer innovations in the ekf were the primary cause of these failures.

Typically, the pre-flight failure flag would trigger immediately upon disarm.

px4 v1.9.0+ seems to have some improvements related to our pre-flight failure problem, including additional log data in estimator_status.msg

As reference, see Octorotor EKF errors

UPGRADE

With upgraded px4 (and mavros), I’m experiencing a new problem now with essentially our same software and configuration.

When upgrading from px4 v1.8.2 to v1.9.0+, some minor changes were required to our gazebo model and world, posix_sitl_default vs. px4_sitl_default, etc.

Perhaps I missed something required for the transition from v1.8.2 to v1.9.0+.

I have tried px4 v1.9.2 and v1.10.1 and mavros v0.31.0, v0.33.0, and v1.0.0.

I’ve only been able to test in SITL (with our modified solo model) and not real flight tests.
We typically want to see our system working well in SITL before attempting any real flight tests.

PROBLEM

Due to their flexibility, we like to use raw setpoints published to /mavros/setpoint_raw/local.

Depending on the state of our system, the bitmask will be set to: (1) vel xyz + yaw, (2) pos xyz + yaw, (3) vel xyz, or (4) pos xyz.

With px4 v1.8.2, raw setpoints have worked very well for us in SITL and real flight tests.

But, with px4 v1.9.0+, only the yaw component of the raw setpoints is executed (causes vehicle motion).

A couple years ago, I wrote a simple offboard figure-8 routine intended for mag calib and safety pilot observation/paranoia.
With px4 v1.8.2, motion of the UAV during the figure-8 routine looks great (in SITL and real flight tests).
With px4 v1.9.0+, I only see yaw motion (in SITL).

Depending on a boolean parameter, this figure-8 routine publishes raw setpoints of either (1) vel xyz + yaw, or (2) pos xyz + yaw.
In both cases, I see the uav rotate (for heading alignment along figure-8 path), but no translational motion.

When I echo the command topic /mavros/setpoint_position/local, the pos+yaw or vel+yaw values look correct.
When I echo the loopback topic /mavros/setpoint_raw/target_local, the position values remain constant (current uav position?) and the velocity values are very small. What does this mean?

When attempting to execute these raw setpoints, QGroundControl does not show any errors or warnings.

With px4 v1.9.0+, I’ve also tried position and velocity setpoints published to /mavros/setpoint_position/local and /mavros/setpoint_velocity/cmd_vel_unstamped

Surprisingly, these two types of setpoints DO appear to work (causes expected vehicle motion).

What am I missing?
What log data can I analyse to understand and fix this problem?
What changes between px4 v1.8.2 and v1.9.0+ may be related?

Thanks for any help you guys can provide. I’m stuck
– John

Without reading all of what you wrote, have you tried 1.10 or master? And if not, why not?

I’m writing this because I doubt you will get much support if you’re on older versions.

Hi, thanks for responding. I have tried v1.9.2 and v1.10.1 release tags of px4 along with v0.31.0, v0.33.0, and v1.0.0 releases of mavros. With all of these different versions, including latest px4+mavros, I have the same problem with raw setpoint. As sanity check, I reverted to our older software versions, px4 v1.8.2 and mavros v0.31.0, and the raw setpoint works as expected. Are there any specific px4 log messages that might contain useful diagnostic data?

Let me ping @TSC21 and @mhkabir.

Cool thanks. I just started reviewing the mavros setpoint loopback topic published in mavros/src/plugins/setpoint_raw.cpp to understand the meaning of values nearly equal to zero, and then hopefully have some new ideas about what to try next. At the moment, I’m assuming a small loopback value indicates the px4 rejected the setpoint. I suppose its also possible the setpoint message received by px4 (from mavros) somehow contains bad data.

@j-co the setpoint_raw plugin hasn’t changed for a while now, so this would have to be in the way that the offboard setpoints are now processed in PX4 (from 1.9.0) and probably how the control loops are tuned and how that influences in your case. I would start by comparing the mavlink_receiver code in PX4 for the offboard setpoints processing between 1.8.2 and 1.9.0 and check what changes might have influenced the behaviour. I would even say that it has to be with the bitmask and the way it is being set on your side.

For anyone interested, here is a description of the problem and a solution.

The problem turned out to be with the type mask of the raw setpoint.

In px4 v1.9.0+, the last 4 bits of the uint16 mask are important, whereas in px4 v1.8.2 and earlier, these bits don’t seem to matter.

Looking at the relevant message descriptions in mavros and mavlink documentation, they both say nothing about these last four bits.

http://docs.ros.org/api/mavros_msgs/html/msg/PositionTarget.html
https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED
https://mavlink.io/en/messages/common.html#POSITION_TARGET_LOCAL_NED
https://mavlink.io/en/messages/common.html#POSITION_TARGET_TYPEMASK

Clearly, only the first 12 bits (within 16 bit unsigned int) are defined, i.e. 2^(#bits-1) = largest value and 2^(12-1) = 2048

In px4 v1.8.2, the following mask works for commanding velocity+yaw

mavros_msgs::PositionTarget lCmdMsg;

lCmdMsg.type_mask = ~(
mavros_msgs::PositionTarget::IGNORE_VX |
mavros_msgs::PositionTarget::IGNORE_VY |
mavros_msgs::PositionTarget::IGNORE_VZ |
mavros_msgs::PositionTarget::IGNORE_YAW);

However, this mask does not work properly in px4 v1.9.0+.

To get this working in px4 v1.9.0+, the following changes were made

// uint16_t, upper 4 bits, 1111,0000,0000,0000 = 2^16 - 2^12 = 61440
mavros_msgs::PositionTarget::_type_mask_type upper4bitsOn = 61440u;

mavros_msgs::PositionTarget lCmdMsg;

lCmdMsg.type_mask = ~(
mavros_msgs::PositionTarget::IGNORE_VX |
mavros_msgs::PositionTarget::IGNORE_VY |
mavros_msgs::PositionTarget::IGNORE_VZ |
mavros_msgs::PositionTarget::IGNORE_YAW |
upper4bitsOn );

The only difference between these two masks is the last four bits being either all 1’s or 0’s.

I’ve tried this with various combinations of control variables, and it seems to work in all cases.

1 Like

TSC21, thanks for your guidance. I appreciate the hard work by you and all of the other developers

1 Like