Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Draft] Fix SITL offboard attitude for VTOL_TYPE_RESERVED2 #13122

Closed
wants to merge 3 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1397,6 +1397,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_HELICOPTER:
case MAV_TYPE_VTOL_RESERVED2:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this specific only for this VTOL type?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure how thrust is handled in the other VTOL types, so I preferred to leave it blank for those types. I only work on quadplanes.

Also, my newly added switch on lines 1410-1417 eventually needs to be updated with the other VTOL types (preferably by someone who knows the other types, not that I make a stupid mistake)

att_sp.thrust_body[2] = -set_attitude_target.thrust;
Comment on lines +1400 to 1401
Copy link
Contributor

@jlecoeur jlecoeur Oct 9, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This will work only in MC mode, att_sp.thrust_body[0] should be used when in fixed-wing mode.

Copy link
Contributor

@irsdkv irsdkv Oct 9, 2019

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

break;

Expand All @@ -1406,7 +1407,15 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
}
}

_att_sp_pub.publish(att_sp);
switch (_mavlink->get_system_type()) {
case MAV_TYPE_VTOL_RESERVED2:
_virt_att_sp_pub.publish(att_sp);
break;

default:
_att_sp_pub.publish(att_sp);
break;
}
}

/* Publish attitude rate setpoint if bodyrate and thrust ignore bits are not set */
Expand Down
1 change: 1 addition & 0 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,7 @@ class MavlinkReceiver : public ModuleParams
uORB::Publication<position_setpoint_triplet_s> _pos_sp_triplet_pub{ORB_ID(position_setpoint_triplet)};
uORB::Publication<vehicle_attitude_s> _attitude_pub{ORB_ID(vehicle_attitude)};
uORB::Publication<vehicle_attitude_setpoint_s> _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)};
uORB::Publication<vehicle_attitude_setpoint_s> _virt_att_sp_pub{ORB_ID(mc_virtual_attitude_setpoint)};
uORB::Publication<vehicle_global_position_s> _global_pos_pub{ORB_ID(vehicle_global_position)};
uORB::Publication<vehicle_gps_position_s> _gps_pub{ORB_ID(vehicle_gps_position)};
uORB::Publication<vehicle_land_detected_s> _land_detector_pub{ORB_ID(vehicle_land_detected)};
Expand Down