#####
#
# This file maps all the topics that are to be used on the uXRCE-DDS client.
#
#####
publications:

  - topic: /fmu/out/battery_status
    type: px4_msgs::msg::BatteryStatus
    rate_limit: 1.

  # - topic: /fmu/out/sensor_combined
  #   type: px4_msgs::msg::SensorCombined

  - topic: /fmu/out/vehicle_angular_velocity
    type: px4_msgs::msg::VehicleAngularVelocity
    rate_limit: 50.

  - topic: /fmu/out/vehicle_attitude
    type: px4_msgs::msg::VehicleAttitude
    rate_limit: 50.

  - topic: /fmu/out/vehicle_control_mode
    type: px4_msgs::msg::VehicleControlMode
    rate_limit: 50.

  - topic: /fmu/out/vehicle_local_position
    type: px4_msgs::msg::VehicleLocalPosition
    rate_limit: 50.

  - topic: /fmu/out/vehicle_odometry
    type: px4_msgs::msg::VehicleOdometry
    rate_limit: 100.

  - topic: /fmu/out/vehicle_status
    type: px4_msgs::msg::VehicleStatus
    rate_limit: 5.

  - topic: /fmu/out/actuator_motors
    type: px4_msgs::msg::ActuatorMotors
    rate_limit: 50.

  - topic: /fmu/out/vehicle_torque_setpoint
    type: px4_msgs::msg::VehicleTorqueSetpoint
    rate_limit: 50.

  - topic: /fmu/out/vehicle_thrust_setpoint
    type: px4_msgs::msg::VehicleThrustSetpoint
    rate_limit: 50.

  # - topic: /fmu/out/log_message
  #   type: px4_msgs::msg::LogMessage

  # - topic: /fmu/out/mavlink_log
  #   type: px4_msgs::msg::MavlinkLog

  - topic: /fmu/out/rc_channels
    type: px4_msgs::msg::RcChannels
    rate_limit: 10.

  - topic: /fmu/out/vehicle_rates_setpoint
    type: px4_msgs::msg::VehicleRatesSetpoint
    rate_limit: 50.

  - topic: /fmu/out/vehicle_command
    type: px4_msgs::msg::VehicleCommand
    rate_limit: 50.

subscriptions:

  - topic: /fmu/in/arming_check_reply
    type: px4_msgs::msg::ArmingCheckReply

  - topic: /fmu/in/manual_control_input
    type: px4_msgs::msg::ManualControlSetpoint

  - topic: /fmu/in/offboard_control_mode
    type: px4_msgs::msg::OffboardControlMode

  - topic: /fmu/in/onboard_computer_status
    type: px4_msgs::msg::OnboardComputerStatus

  - topic: /fmu/in/telemetry_status
    type: px4_msgs::msg::TelemetryStatus

  - topic: /fmu/in/trajectory_setpoint
    type: px4_msgs::msg::TrajectorySetpoint

  - topic: /fmu/in/vehicle_attitude_setpoint
    type: px4_msgs::msg::VehicleAttitudeSetpoint

  - topic: /fmu/in/vehicle_rates_setpoint
    type: px4_msgs::msg::VehicleRatesSetpoint

  - topic: /fmu/in/vehicle_visual_odometry
    type: px4_msgs::msg::VehicleOdometry

  - topic: /fmu/in/vehicle_command
    type: px4_msgs::msg::VehicleCommand

  - topic: /fmu/in/vehicle_thrust_setpoint
    type: px4_msgs::msg::VehicleThrustSetpoint

  - topic: /fmu/in/vehicle_torque_setpoint
    type: px4_msgs::msg::VehicleTorqueSetpoint

  - topic: /fmu/in/actuator_motors
    type: px4_msgs::msg::ActuatorMotors

  - topic: /fmu/in/actuator_servos
    type: px4_msgs::msg::ActuatorServos

# Subscriptions multiplexed to uORB multi-instances (optionally demultiplexed based on a message field)
subscriptions_multi:
  # - topic: /fmu/in/aux_global_position
  #   type: px4_msgs::msg::AuxGlobalPosition
  #   route_field: id
  #   max_instances: 4
