Open DavidBSaba opened 4 years ago
@bresch there is a parameter for this, right?
@DavidBSaba have you tried with 1.10 or master?
@DavidBSaba I had a similar problem for vtols. I tested with gazebo_iris instead and had no issues setting the yaw at mission waypoints, but the same mission failed for vtol (in copter mode of course)
@julianoes @dayjaby thank you for your reply. In fact I have tested the versions 1.8.0 stable (the one I use) , 1.10.0 stable (a sufficiently recent version) and a Master version by simulating through Gazebo. And here are the results:
I solved this problem by setting an Offset to the yaw using the parameter 'MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET', and changed the code in mission.cpp line 1271 from yaw += _navigator->get_vroi().yaw_offset; to yaw = _navigator->get_vroi().yaw_offset;
Now the yaw_offset is considered as the desired yaw (behaves like 'param4'), and it is fixed during all the mission for all the waypoints in MC mode once declared. The value can be modified if another MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET is used in another waypoint or cancelled by 'MAV_CMD_DO_SET_ROI_NONE' command (cancel ROI).
Note to self: MAV_CMD_NAV_WAYPOINT.param4 refers to rotary wing. Should probably be changed to also capture VTOL. E.g. "vehicles/modes that support independent direction of travel and yaw (e.g. multirotors).
@DavidBSaba nice hack! Did you use a special MPC_YAW_MODE to achieve that?
@dayjaby yes the MIS_YAWMODE (recently renamed MC_YAW_MODE) should be set to 1. But you can bypass it in the code by eliminating the condition in the 'if' loop in the mission.cpp file.
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.
Does this method still work? When I follow this method, it is not working.
Hello I am facing a problem fixing the heading of a drone in mission flight. I am currently using Pixhawk 2 cube and the PX4 software (version 1.8.0 stable) on VTOL tailsitter quadcopter.
I want to program a mission where I can fix the heading of the vehicle (MC mode) to a predefined value. I am using the QGroundControl (DailyBuild version) on Ubuntu. I have tried to set the param4 of the Waypoints to the desired heading (in degrees). The parameters related to the mount are disabled and the parameter MIS_YAW_MODE is 0. However, that didn't work. The drone's heading is towards the next waypoint. I have remarked that in the Firmware code, the param4 is taken into consideration only when cmd.command == vehicle_command_s::VEHICLE_CMD_DO_REPOSITION, or cmd.command == vehicle_command_s::VEHICLE_CMD_NAV_TAKEOFF,which I think is far from being our case.
The other thing I tried to do is to set an ROI with mount being disabled. Interestingly, that seemed to work properly in some missions. Check for instance Mission 1: https://logs.px4.io/plot_app?log=e508f3c8-46a7-40ef-a85a-a0d6ea01cfd1 The ROI is set at North-West, and we can see the yaw setpoint at about -40 degrees and held during the whole mission.
However, in other flight tests, the yaw setpoint does not correspond to the ROI fixed in QGC. I have remarked, in two missions I have done, that the controller gives a yaw setpoint about -173.19 degrees:
Mission 2 ( test made in 16 January 2020 with Pixwak 2 cube) https://logs.px4.io/plot_app?log=2f0b375e-380c-4042-9ebf-93323c94c9fd
In this mission, the ROI is fixed after the takeOff at the North-East (we were thus expecting a heading setpoint about 55 degrees). We got instead a yaw setpoint -173.19 degrees.
Mission 3 ( test made in 10 May 2019 using Pixhawk 3 pro) https://review.px4.io/plot_app?log=6462bbe3-b70d-4ef4-a01f-5d62d29c69a2 This mission had been done twice, and in both the yaw setpoint is equal to -173.19 degrees, exact same value as that in the mission above (this value is not the value expected for the fixed ROI).
I kindly ask if there is a bug in the software or anyone has any idea of the cause of this inconsistency? And is there a way to set the desired heading using a parameter in QGroundControl (param4 or other)?