Closed gspark87 closed 10 months ago
When I applied this code to the fixed wing, it doesn't work.
@gspark87 Could you elaborate on what "doesn't work" mean?
Should I use MAVLink(mavros) instead of ROS2 message(px4_msgs) in the fixed-wing offboard control?
Either should work, if you are interested in creating a specific example, I would be interested in collaborating.
@Jaeyoung-Lim Thank you for reply. I modified it as below by referring to your code. It doesn't work as intended to fixed-wing(FW). env) ubuntu 22.04 / ROS2 humble / PX4 1.15.0alpha
def cmdloop_callback(self):
# Publish offboard control modes
if MODE == 'POS':
offboard_msg = OffboardControlMode()
offboard_msg.timestamp = int(Clock().now().nanoseconds / 1000)
offboard_msg.position=True
offboard_msg.velocity=False
offboard_msg.acceleration=False
self.publisher_offboard_mode.publish(offboard_msg)
if self.nav_state == VehicleStatus.NAVIGATION_STATE_OFFBOARD:
trajectory_msg = TrajectorySetpoint()
trajectory_msg.position[0] = 100.0
trajectory_msg.position[1] = 100.0
trajectory_msg.position[2] = -60.0
self.publisher_trajectory.publish(trajectory_msg)
if MODE == 'ATT':
offboard_msg = OffboardControlMode()
offboard_msg.timestamp = int(Clock().now().nanoseconds / 1000)
offboard_msg.position=False
offboard_msg.velocity=False
offboard_msg.acceleration=False
offboard_msg.attitude=True
self.publisher_offboard_mode.publish(offboard_msg)
if self.nav_state == VehicleStatus.NAVIGATION_STATE_OFFBOARD:
quat = navpy.angle2quat(45.0, -20.0, 30.0, input_unit='deg', rotation_sequence='ZYX')
att_msg = VehicleAttitudeSetpoint()
att_msg.q_d = [quat[0], quat[1][0], quat[1][1], quat[1][2]]
att_msg.thrust_body = [0.6, 0.0, 0.0]
self.publisher_attitude.publish(att_msg)
Could you elaborate on what "doesn't work" mean?
Problem
self.vehicle_command(VehicleCommand().VEHICLE_CMD_DO_SET_MODE, 1.0, 6.0)
Either should work,
I don't try to MAVLink yet. In PX4 User Guide, It seems like only Copter is available for ROS2 Messages such as px4_msgs::msg::TrajectorySetpoint
and px4_msgs::msg::VehicleAttitudeSetpoint
.
https://docs.px4.io/main/en/flight_modes/offboard.html
if you are interested in creating a specific example, I would be interested in collaborating.
When the problem is resolved, I will share it.
@gspark87
In offboard position control, FW do not fly to position setpoint. The type_mask(position) exist in MAVLink message, but not in px4_msgs.
The current implementation for fixedwing offboard trajectory setpoints requires you to provide the velocity setpoints, which is interpreted as ground speed.
To use position-only setpoints for offboard mode, you can use https://github.com/PX4/PX4-Autopilot/pull/21376
Here is a flight log in SITL showing how offboard mode is working with only position setpoints: https://review.px4.io/plot_app?log=3e50cfeb-ffb5-41fa-9fab-ad5b797207c8
Note that you additionally need to populate the velocity setpoints with nan
values for it to get ignored, since the messages from python get initialized as zeros(which are valid). We will have a more cleaner interface in https://github.com/PX4/PX4-Autopilot/pull/22530, where the inputs will be sanity checked.
In offboard attitude control, FW does not maneuver to desired quaternion. The trust_body command works and can also be seen that the thrust changes in QGC.
This might be the case, since yaw is normally not controlled for fixed-wing vehicles. Have you tried setting the body relative euler angles(https://github.com/PX4/px4_msgs/blob/e6e0a4d5e2b29868798c5fbc62f30ca8658d63e1/msg/VehicleAttitudeSetpoint.msg#L3-L5)?
There is an offboard button in QGC of Multicopter, but not in fixedwing. I changed the offboard mode using px4_msgs. Why offboard button doesn't find on FW in QGC?
This seems like a bug in QGC that might be worth raising.
You can also simply type commander mode offboard
in the px4 shell if you are running SITL
Hope this helps and please let me know if it worked for you!
Note that you additionally need to populate the velocity setpoints with nan values for it to get ignored, since the messages from python get initialized as zeros(which are valid).
Fixedwing offboard position control was solved immediately by velocity setpoints with nan
.
trajectory_msg = TrajectorySetpoint()
trajectory_msg.position[0] = -100.0 # North
trajectory_msg.position[1] = -100.0 # East
trajectory_msg.position[2] = -60.0 # Down
trajectory_msg.velocity[0] = math.nan # solved
trajectory_msg.velocity[1] = math.nan
trajectory_msg.velocity[2] = math.nan
self.publisher_trajectory.publish(trajectory_msg)
Have you tried setting the body relative euler angles?
As you advised, I used body angle roll_body
, pitch_body
instead of quaternion q_d
, so it was solved.
But, yaw_body
is not working.
This seems like a bug in QGC that might be worth raising. You can also simply type commander mode offboard in the px4 shell if you are running SITL
Thanks for letting me know.
But, yaw_body is not working.
@gspark87 You might want to raise this directly in the PX4 repository, since this is more related to the flight control side, rather than this repository.
May I ask you what you are trying to do with just position and attitude references? Just curious in general why you would want to control full attitude or position without the velocity component.
For context, the trajectory setpoint interface was primarily made for path tracking for low altitude terrain navigation (https://github.com/ethz-asl/terrain-navigation)
@Jaeyoung-Lim Happy new year!
May I ask you what you are trying to do with just position and attitude references?
I am trying to fly autonomously with reinforcement learning. I was studying setpoint interfaces step by step, considering the communication of RL agent and PX4.
Here is the code I tested. https://github.com/gspark87/px4_offboard/
@gspark87 Thank you for sharing your solution.
However, It appears you have made a copy of the code in this repository and removed the licenses.
Could you explain why you have removed the license headers? The license requires for the header to be included.
(From the license)
1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
@Jaeyoung-Lim I'm sorry, added the license in this code. Is it okay if I do this?
Hello, I'm looking for fixed-wing offboard example on ROS2.
When I applied this code to the fixed wing, it doesn't work. Should I use MAVLink(mavros) instead of ROS2 message(px4_msgs) in the fixed-wing offboard control?