Why does acceleration control in offboard mode need velocity estimate?

Hello, I am using the PX4 v1.15.0 firmware. I am trying to add additional behaviour to my drone by using offboard mode and publishing offboard_control_mode and trajectory_setpoint messages from my module inside PX4.

The drone needs to operate in environments without GPS or a velocity estimate, so I was trying to implement something similar to the altitude mode, where we control z velocity and xy acceleration. But it seems like (according to the table below from the docs) offboard acceleration requires a velocity estimate.

I am publishing the following offboard control mode message:

// Publish an offboard control mode message
offboard_control_mode_s ocm;
ocm.timestamp = hrt_absolute_time();
ocm.position = false;
ocm.velocity = false;
ocm.acceleration = true;
ocm.attitude = true;
ocm.body_rate = false;
ocm.thrust_and_torque = false;
ocm.direct_actuator = false;
_offboard_control_mode_pub.publish(ocm);

and the following trajectory_control message:

trajectory_setpoint_s trajectory_setpoint;
trajectory_setpoint.timestamp = hrt_absolute_time();

trajectory_setpoint.position[0] = NAN;
trajectory_setpoint.position[1] = NAN;
trajectory_setpoint.position[2] = NAN;

trajectory_setpoint.velocity[0] = NAN;
trajectory_setpoint.velocity[1] = NAN;
trajectory_setpoint.velocity[2] = 1;

trajectory_setpoint.acceleration[0] = 1;
trajectory_setpoint.acceleration[1] = 1;
trajectory_setpoint.acceleration[2] = NAN;

trajectory_setpoint.jerk[0] = NAN;
trajectory_setpoint.jerk[1] = NAN;
trajectory_setpoint.jerk[2] = NAN;

trajectory_setpoint.yaw = _target_attitude_absolute_euler.psi();
trajectory_setpoint.yawspeed = NAN;

_trajectory_setpoint_pub.publish(trajectory_setpoint);

From my understanding the xy acceleration in PX4 is not closed loop and is just directly mapped to an attitude setpoint, so it shouldnā€™t need either a position or velocity estimate. It looks like the altitude mode does the same as what I have done here as well, by publishing a trajectory_setpoint message with xy acceleration and z velocity.

If I change the offboard check in src/modules/commander/HealthAndArmingChecks/checks/offboardCheck.cpp to remove the check on acceleration then my code seems to work fine in SITL simulation, I can command accelerations in offboard mode without GPS.

		if (offboard_control_mode.position && reporter.failsafeFlags().local_position_invalid) {
			offboard_available = false;

		} else if (offboard_control_mode.velocity && reporter.failsafeFlags().local_velocity_invalid) {
			offboard_available = false;

		}
		// else if (offboard_control_mode.acceleration && reporter.failsafeFlags().local_velocity_invalid) {
		// 	// OFFBOARD acceleration handled by position controller
		// 	offboard_available = false;
		// }

I am just wondering if there is an issue with the logic here or there is some case I have not thought of where velocity estimates would be required for acceleration control?

Thanks

@Benja Is this something you can advise on?

Why did you set ocm.velocity = false; while commanding z velocity?

Thanks @hamishwillee for pinging this.

@ra1nyu I think it worth rising your point (removing velocity requirement when using offboard acceleration setpoints) at the next community meeting. I too donā€™t see a reason having that check.

@Mohan_Dasari , the OffboardControlMode flags pos, vel, acc are only used in to check the feasibility of the mode and they are not used in the controller itself. The controller checks the fields of the TrajectorySetpoint message and then decides which controller (pos or vel) needs to run. As there are no separate v_speed and h_speed flags velocity was set to off otherwise no offboard would have been possible (no h_speed available). However, with valid h_speed @ra1nyu was still able to control vertical velocity.

Thanks for the replies everyone.

Yes, I realized that the offboard control mode message was only used for checking the feasibility of the mode in the commander, thatā€™s why I thought whether the velocity and acceleration flags were set or not didnā€™t matter. But I tried setting both of them to false to trick Commander into allowing it, and while Commander allowed me to switch the mode, it also ended up disabling the multicopter position control module, so the drone crashed (in SITL). So I kept the acceleration mode enabled so at least the MPC module would be running.

@Benja thank you, when you say the community meeting, are you talking about the weekly coordination calls?

I also had the idea to introduce a new offboard control mode ā€œaltitudeā€ which would have the same checks and commands as the px4 internal altitude mode, but obviously this would be more complicated. We would at least have to add another case in src/modules/commander/ModeUtil/control_mode.cpp and of course in the offboardCheck.cpp for it but I am not sure if itā€™s called anywhere else too.

Yes, those ones: here is todayā€™s link PX4 Sync / Q&A: Dec 4, 2024

1 Like

Here I made a pr based on our discussion in the dev call:

@ra1nyu could you quickly check if that does the trick for you? Sorry I donā€™t know your GitHub handle to tag.

Also we should review if thereā€™s a reason in the history why thatā€™s should not be a good idea but otherwise I consider it an oversight.

Thanks @MaEtUgR the code looks good to me. I will give it a test in SITL to see if it behaves as I expect.