ardupilot/libraries/AP_DDS/dds_xrce_profile.xml
pedro-fuoco e1b06a1b99 AP_DDS: Integrate AP_BattMonitor to work with AP_DDS
* Edit BatteryState.idl
* Add BatteryState to AP_DDS_Topic_table.h
* Add BatteryState to the DDS Client
	* Add voltage
	* Add temperature
	* Add current
	* Add charge
	* Add capacity with NAN value
	* Add design_capacity
	* Add percentage
	* Add power_supply_status
	* Add power_supply_health
	* Add power_supply_technology with 0 value
	* Add present
	* Cell_voltage and Serial_number need to be implemented in the future
	* Did not add cell_temperature as AP_BattMonitor doesn't support it
	* Did not add location as this is a generic implementation
* Parameterize battery instance number
2023-04-15 09:40:33 +10:00

115 lines
3.1 KiB
XML

<?xml version="1.0"?>
<profiles>
<participant profile_name="participant_profile">
<rtps>
<name>Ardupilot_DDS_XRCE_Client</name>
</rtps>
</participant>
<topic profile_name="time__t">
<name>rt/ROS2_Time</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
<data_writer profile_name="time__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>RELIABLE</kind>
</reliability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_Time</name>
<dataType>builtin_interfaces::msg::dds_::Time_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
</data_writer>
<topic profile_name="navsatfix0__t">
<name>rt/ROS2_NavSatFix0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>5</depth>
</historyQos>
</topic>
<data_writer profile_name="navsatfix0__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>BEST_EFFORT</kind>
</reliability>
<durability>
<kind>VOLATILE</kind>
</durability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_NavSatFix0</name>
<dataType>sensor_msgs::msg::dds_::NavSatFix_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>5</depth>
</historyQos>
</topic>
</data_writer>
<topic profile_name="statictransforms__t">
<name>rt/tf</name>
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>1</depth>
</historyQos>
</topic>
<data_writer profile_name="statictransforms__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>RELIABLE</kind>
</reliability>
<durability>
<kind>TRANSIENT_LOCAL</kind>
</durability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/tf</name>
<dataType>tf2_msgs::msg::dds_::TFMessage_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>1</depth>
</historyQos>
</topic>
</data_writer>
<topic profile_name="batterystate0__t">
<name>rt/ROS2_BatteryState0</name>
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
<data_writer profile_name="batterystate0__dw">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
<qos>
<reliability>
<kind>RELIABLE</kind>
</reliability>
</qos>
<topic>
<kind>NO_KEY</kind>
<name>rt/ROS2_BatteryState0</name>
<dataType>sensor_msgs::msg::dds_::BatteryState_</dataType>
<historyQos>
<kind>KEEP_LAST</kind>
<depth>20</depth>
</historyQos>
</topic>
</data_writer>
</profiles>