mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
Copy the uxrce config for Zenoh
This commit is contained in:
committed by
Beat Küng
parent
80b5cf2ed7
commit
7a98c87fcb
@@ -86,11 +86,11 @@ endif()
|
||||
add_custom_command(OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/default_topics.c
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/../uxrce_dds_client/generate_dds_topics.py
|
||||
--client-outdir ${CMAKE_CURRENT_BINARY_DIR}
|
||||
--dds-topics-file ${CMAKE_CURRENT_SOURCE_DIR}/../uxrce_dds_client/dds_topics.yaml
|
||||
--dds-topics-file ${CMAKE_CURRENT_SOURCE_DIR}/dds_topics.yaml
|
||||
--template_file ${CMAKE_CURRENT_SOURCE_DIR}/default_topics.c.em
|
||||
DEPENDS
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../uxrce_dds_client/generate_dds_topics.py
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../uxrce_dds_client/dds_topics.yaml
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/dds_topics.yaml
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/default_topics.c.em
|
||||
COMMENT "Generating Default config"
|
||||
)
|
||||
|
||||
@@ -0,0 +1,161 @@
|
||||
#####
|
||||
#
|
||||
# This file maps all the topics that are to be used on the uXRCE-DDS client.
|
||||
#
|
||||
#####
|
||||
publications:
|
||||
|
||||
- topic: /fmu/out/register_ext_component_reply
|
||||
type: px4_msgs::msg::RegisterExtComponentReply
|
||||
|
||||
- topic: /fmu/out/arming_check_request
|
||||
type: px4_msgs::msg::ArmingCheckRequest
|
||||
|
||||
- topic: /fmu/out/mode_completed
|
||||
type: px4_msgs::msg::ModeCompleted
|
||||
|
||||
- topic: /fmu/out/battery_status
|
||||
type: px4_msgs::msg::BatteryStatus
|
||||
|
||||
- topic: /fmu/out/collision_constraints
|
||||
type: px4_msgs::msg::CollisionConstraints
|
||||
|
||||
- topic: /fmu/out/estimator_status_flags
|
||||
type: px4_msgs::msg::EstimatorStatusFlags
|
||||
|
||||
- topic: /fmu/out/failsafe_flags
|
||||
type: px4_msgs::msg::FailsafeFlags
|
||||
|
||||
- topic: /fmu/out/manual_control_setpoint
|
||||
type: px4_msgs::msg::ManualControlSetpoint
|
||||
|
||||
- topic: /fmu/out/message_format_response
|
||||
type: px4_msgs::msg::MessageFormatResponse
|
||||
|
||||
- topic: /fmu/out/position_setpoint_triplet
|
||||
type: px4_msgs::msg::PositionSetpointTriplet
|
||||
|
||||
- topic: /fmu/out/sensor_combined
|
||||
type: px4_msgs::msg::SensorCombined
|
||||
|
||||
- topic: /fmu/out/timesync_status
|
||||
type: px4_msgs::msg::TimesyncStatus
|
||||
|
||||
# - topic: /fmu/out/vehicle_angular_velocity
|
||||
# type: px4_msgs::msg::VehicleAngularVelocity
|
||||
|
||||
- topic: /fmu/out/vehicle_land_detected
|
||||
type: px4_msgs::msg::VehicleLandDetected
|
||||
|
||||
- topic: /fmu/out/vehicle_attitude
|
||||
type: px4_msgs::msg::VehicleAttitude
|
||||
|
||||
- topic: /fmu/out/vehicle_control_mode
|
||||
type: px4_msgs::msg::VehicleControlMode
|
||||
|
||||
- topic: /fmu/out/vehicle_command_ack
|
||||
type: px4_msgs::msg::VehicleCommandAck
|
||||
|
||||
- topic: /fmu/out/vehicle_global_position
|
||||
type: px4_msgs::msg::VehicleGlobalPosition
|
||||
|
||||
- topic: /fmu/out/vehicle_gps_position
|
||||
type: px4_msgs::msg::SensorGps
|
||||
|
||||
- topic: /fmu/out/vehicle_local_position
|
||||
type: px4_msgs::msg::VehicleLocalPosition
|
||||
|
||||
- topic: /fmu/out/vehicle_odometry
|
||||
type: px4_msgs::msg::VehicleOdometry
|
||||
|
||||
- topic: /fmu/out/vehicle_status
|
||||
type: px4_msgs::msg::VehicleStatus
|
||||
|
||||
- topic: /fmu/out/airspeed_validated
|
||||
type: px4_msgs::msg::AirspeedValidated
|
||||
|
||||
# Create uORB::Publication
|
||||
subscriptions:
|
||||
- topic: /fmu/in/register_ext_component_request
|
||||
type: px4_msgs::msg::RegisterExtComponentRequest
|
||||
|
||||
- topic: /fmu/in/unregister_ext_component
|
||||
type: px4_msgs::msg::UnregisterExtComponent
|
||||
|
||||
- topic: /fmu/in/config_overrides_request
|
||||
type: px4_msgs::msg::ConfigOverrides
|
||||
|
||||
- topic: /fmu/in/arming_check_reply
|
||||
type: px4_msgs::msg::ArmingCheckReply
|
||||
|
||||
- topic: /fmu/in/message_format_request
|
||||
type: px4_msgs::msg::MessageFormatRequest
|
||||
|
||||
- topic: /fmu/in/mode_completed
|
||||
type: px4_msgs::msg::ModeCompleted
|
||||
|
||||
- topic: /fmu/in/config_control_setpoints
|
||||
type: px4_msgs::msg::VehicleControlMode
|
||||
|
||||
- topic: /fmu/in/distance_sensor
|
||||
type: px4_msgs::msg::DistanceSensor
|
||||
|
||||
- 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/obstacle_distance
|
||||
type: px4_msgs::msg::ObstacleDistance
|
||||
|
||||
- topic: /fmu/in/sensor_optical_flow
|
||||
type: px4_msgs::msg::SensorOpticalFlow
|
||||
|
||||
- topic: /fmu/in/goto_setpoint
|
||||
type: px4_msgs::msg::GotoSetpoint
|
||||
|
||||
- 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_mocap_odometry
|
||||
type: px4_msgs::msg::VehicleOdometry
|
||||
|
||||
- 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_command_mode_executor
|
||||
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
|
||||
|
||||
- topic: /fmu/in/aux_global_position
|
||||
type: px4_msgs::msg::VehicleGlobalPosition
|
||||
|
||||
# Create uORB::PublicationMulti
|
||||
subscriptions_multi:
|
||||
Reference in New Issue
Block a user