Issue with thrust in uuv_hippocampus SITL

Hi,
I’m sending attitude and thrust setpoint to /mavros/setpoint_raw/attitude.

def send_att(self):
    self.rate = rospy.Rate(10)  # Hz
    self.att.body_rate = Vector3(0, 1, 0)
    self.att.header = Header()
    self.att.header.frame_id = "base_footprint"
    self.att.orientation = Quaternion(*quaternion_from_euler(0, 0,
                                                             0))
    self.att.thrust = 0.2
    self.att.type_mask = 7  # ignore body rate
    pitch = 0.0
    inc = 0.01
    while not rospy.is_shutdown():
        pitch = (pitch + inc) % 3.14
        self.att.header.stamp = rospy.Time.now()
        self.att.orientation = Quaternion(*quaternion_from_euler(0, pitch,
                                                                 0))
        self.att.thrust = 0.2
        self.att_pub.publish(self.att)                
        self.rate.sleep()

Here is the output mavros and px4 uORB message.

rostopic echo /mavros/setpoint_raw/target_attitude 
header: 
  seq: 15315
  stamp: 
    secs: 1586413930
    nsecs: 457043968
  frame_id: ''
type_mask: 0
orientation: 
  x: 5.55111512313e-17
  y: 0.86240426237
  z: 5.55111512313e-17
  w: 0.506220276227
body_rate: 
  x: 0.0
  y: 0.0
  z: 0.0
thrust: 0.20000000298

pxh> listener vehicle_attitude_setpoint
TOPIC: vehicle_attitude_setpoint
vehicle_attitude_setpoint_s
timestamp: 1825176000 (0.004000 seconds ago)
roll_body: 0.0000
pitch_body: -0.1200
yaw_body: 1.5708
yaw_sp_move_rate: 0.0000
q_d: [-0.7058, -0.0424, 0.0424, -0.7058]
thrust_body: [0.2000, 0.0000, 0.0000]
roll_reset_integral: False
pitch_reset_integral: False
yaw_reset_integral: False
fw_control_yaw: False
apply_flaps: 0

The vehicle doesn’t have a forward thrust. I want to get the vehicle moving forward than just pitch as can been seen in this video https://streamable.com/pf76py.
Few things that I’m confused here:

  1. I am publishing att.body_rate = Vector3(0, 1, 0) and the mavros target attitude shows (0,0,0). I believe this is due to the mask and values are ignored (or set to zeroes). But I do not understand how pxh> listener vehicle_attitude_setpoint shows pitch_body and yaw_body as not zero. (also do they represent body rate?).

  2. I was able to fix this issue (of no thrust) and get thrust yesterday by changing PX4-Autopilot/src/modules/uuv_att_control/uuv_att_control.cpp at 36f836be79760409165030edfadf25ea68885a1e · PX4/PX4-Autopilot · GitHub
    thrust_u = _param_direct_thrust.get(); to
    thrust_u = _vehicle_attitude_sp.thrust_body[0];.

Can someone correct me, if what I’m doing here is wrong.
My goal is to send attitude and thrust to uuv_hippocampus in SITL.