diff --git a/.vscode/browse.vc.db b/.vscode/browse.vc.db new file mode 100644 index 00000000..73f297a9 Binary files /dev/null and b/.vscode/browse.vc.db differ diff --git a/.vscode/browse.vc.db-shm b/.vscode/browse.vc.db-shm new file mode 100644 index 00000000..d27eebf9 Binary files /dev/null and b/.vscode/browse.vc.db-shm differ diff --git a/.vscode/browse.vc.db-wal b/.vscode/browse.vc.db-wal new file mode 100644 index 00000000..e69de29b diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 00000000..12cd87c0 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,21 @@ +{ + "configurations": [ + { + "browse": { + "databaseFilename": "${workspaceFolder}/.vscode/browse.vc.db", + "limitSymbolsToIncludedHeaders": false + }, + "includePath": [ + "/opt/ros/humble/include/**", + "/home/nlg/px4_ros_com/include/**", + "/usr/include/**" + ], + "name": "ros2", + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/gcc", + "cStandard": "gnu11", + "cppStandard": "c++17" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json index 0f4d0a0f..b425b7a7 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -2,5 +2,14 @@ "files.associations": { "chrono": "cpp", "ostream": "cpp" - } + }, + "ROS2.distro": "humble", + "python.autoComplete.extraPaths": [ + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ], + "python.analysis.extraPaths": [ + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ] } \ No newline at end of file diff --git a/src/examples/offboard_py/offboard_control.py b/src/examples/offboard_py/offboard_control.py index 7d59f536..6fbdb01b 100755 --- a/src/examples/offboard_py/offboard_control.py +++ b/src/examples/offboard_py/offboard_control.py @@ -13,26 +13,32 @@ def __init__(self) -> None: super().__init__('offboard_control_takeoff_and_land') # Configure QoS profile for publishing and subscribing - qos_profile = QoSProfile( + qos_profile_pub = QoSProfile( reliability=ReliabilityPolicy.BEST_EFFORT, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST, - depth=1 + depth=0 + ) + qos_profile_sub = QoSProfile( + reliability=ReliabilityPolicy.BEST_EFFORT, + durability=DurabilityPolicy.VOLATILE, + history=HistoryPolicy.KEEP_LAST, + depth=10 ) # Create publishers self.offboard_control_mode_publisher = self.create_publisher( - OffboardControlMode, '/fmu/in/offboard_control_mode', qos_profile) + OffboardControlMode, '/fmu/in/offboard_control_mode', qos_profile_pub) self.trajectory_setpoint_publisher = self.create_publisher( - TrajectorySetpoint, '/fmu/in/trajectory_setpoint', qos_profile) + TrajectorySetpoint, '/fmu/in/trajectory_setpoint', qos_profile_pub) self.vehicle_command_publisher = self.create_publisher( - VehicleCommand, '/fmu/in/vehicle_command', qos_profile) + VehicleCommand, '/fmu/in/vehicle_command', qos_profile_pub) # Create subscribers self.vehicle_local_position_subscriber = self.create_subscription( - VehicleLocalPosition, '/fmu/out/vehicle_local_position', self.vehicle_local_position_callback, qos_profile) + VehicleLocalPosition, '/fmu/out/vehicle_local_position', self.vehicle_local_position_callback, qos_profile_sub) self.vehicle_status_subscriber = self.create_subscription( - VehicleStatus, '/fmu/out/vehicle_status', self.vehicle_status_callback, qos_profile) + VehicleStatus, '/fmu/out/vehicle_status', self.vehicle_status_callback, qos_profile_sub) # Initialize variables self.offboard_setpoint_counter = 0