Some probelm of fw attitude control

Hi, guys!
I read the code of fw attitude control recently.
I found the code of attitude control of pixhawk is different from that of ardupilot.
And in the code of pixhawk code,it has a comment line with a key word “jacobian”.
The code as followed:

float ECL_RollController::control_bodyrate(const struct ECL_ControlData &ctl_data)
{
/* Do not calculate control signal with bad inputs */
if (!(PX4_ISFINITE(ctl_data.pitch) &&
PX4_ISFINITE(ctl_data.roll_rate) &&
PX4_ISFINITE(ctl_data.yaw_rate) &&
PX4_ISFINITE(ctl_data.yaw_rate_setpoint) &&
PX4_ISFINITE(ctl_data.airspeed_min) &&
PX4_ISFINITE(ctl_data.airspeed_max) &&
PX4_ISFINITE(ctl_data.scaler))) {
return math::constrain(_last_output, -1.0f, 1.0f);
}

/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
float dt = (float)dt_micros * 1e-6f;

/* lock integral for long intervals */
bool lock_integrator = ctl_data.lock_integrator;

if (dt_micros > 500000) {
	lock_integrator = true;
}

/* Transform setpoint to body angular rates (jacobian) */
_bodyrate_setpoint = _rate_setpoint - sinf(ctl_data.pitch) * ctl_data.yaw_rate_setpoint;

/* Calculate body angular rate error */
_rate_error = _bodyrate_setpoint - ctl_data.roll_rate; //body angular rate error

if (!lock_integrator && _k_i > 0.0f) {

	float id = _rate_error * dt * ctl_data.scaler;

	/*
	* anti-windup: do not allow integrator to increase if actuator is at limit
	*/
	if (_last_output < -1.0f) {
		/* only allow motion to center: increase value */
		id = math::max(id, 0.0f);

	} else if (_last_output > 1.0f) {
		/* only allow motion to center: decrease value */
		id = math::min(id, 0.0f);
	}

	_integrator += id * _k_i;
}

/* integrator limit */
//xxx: until start detection is available: integral part in control signal is limited here
float integrator_constrained = math::constrain(_integrator, -_integrator_max, _integrator_max);
//warnx("roll: _integrator: %.4f, _integrator_max: %.4f", (double)_integrator, (double)_integrator_max);

/* Apply PI rate controller and store non-limited output */
_last_output = _bodyrate_setpoint * _k_ff * ctl_data.scaler +
	       _rate_error * _k_p * ctl_data.scaler * ctl_data.scaler
	       + integrator_constrained;  //scaler is proportional to 1/airspeed

return math::constrain(_last_output, -1.0f, 1.0f);

}

what’s mean of the comment line
“/* Transform setpoint to body angular rates (jacobian) */”?
Thanks for your help!

I think there is no relation to jacobian, just converts Euler angle rates to body rates.