From 721fdd69298c1c8b1fe9141d8d6efe9a06de2ac8 Mon Sep 17 00:00:00 2001 From: Matej Petrlik Date: Thu, 8 Feb 2024 14:40:05 +0100 Subject: [PATCH] added ODOMETRY at 100 Hz to mavlink - topic used for getting UAV state from pixhawk when OLD_PX4_FW=false (default in sim) --- .../ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink | 1 + 1 file changed, 1 insertion(+) diff --git a/ros_packages/mrs_uav_gazebo_simulation/ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink b/ros_packages/mrs_uav_gazebo_simulation/ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink index 4c31e4c..7a65f88 100644 --- a/ros_packages/mrs_uav_gazebo_simulation/ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink +++ b/ros_packages/mrs_uav_gazebo_simulation/ROMFS/px4fmu_common/init.d-posix/px4-rc.mavlink @@ -13,6 +13,7 @@ mavlink stream -r 100 -s ATTITUDE_QUATERNION -u $udp_offboard_port_local # /mavr mavlink stream -r 100 -s ATTITUDE_TARGET -u $udp_offboard_port_local mavlink stream -r 100 -s HIGHRES_IMU -u $udp_offboard_port_local # /mavros/imu/data_raw mavlink stream -r 100 -s LOCAL_POSITION_NED -u $udp_offboard_port_local +mavlink stream -r 100 -s ODOMETRY -u $udp_offboard_port_local mavlink stream -r 100 -s GLOBAL_POSITION_INT -u $udp_offboard_port_local mavlink stream -r 10 -s RC_CHANNELS -u $udp_offboard_port_local mavlink stream -r 10 -s SYS_STATUS -u $udp_offboard_port_local