Skip to content

Commit 6d986a6

Browse files
Add doc folder
1 parent 7561656 commit 6d986a6

File tree

1 file changed

+55
-0
lines changed

1 file changed

+55
-0
lines changed
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/battery_state_broadcaster/doc/userdoc.rst
2+
3+
.. _battery_state_broadcaster_userdoc:
4+
5+
Battery State Broadcaster
6+
=========================
7+
This broadcaster publishes `sensor_msgs/BatteryState <https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/BatteryState.msg>`__ messages from appropriate state interfaces.
8+
9+
10+
Required State Interfaces
11+
---------------------------------
12+
This broadcaster requires the robot to have a sensor component which contains the battery state interfaces:
13+
14+
.. code-block:: xml
15+
16+
<ros2_control type="system">
17+
18+
<!-- ... -->
19+
20+
<sensor name="battery_state">
21+
<state_interface name="voltage" />
22+
</sensor>
23+
</ros2_control>
24+
25+
Parameters
26+
---------------------------------
27+
To use this broadcaster, declare it in the controller manager and set its parameters:
28+
29+
.. code-block:: yaml
30+
31+
controller_manager:
32+
ros__parameters:
33+
battery_state_broadcaster:
34+
type: battery_state_broadcaster/BatteryStateBroadcaster
35+
36+
battery_state_broadcaster:
37+
ros__parameters:
38+
sensor_name: "battery_state"
39+
design_capacity: 100.0
40+
# https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/BatteryState.msg
41+
power_supply_technology: 2
42+
43+
And spawn it in the launch file:
44+
45+
.. code-block:: python
46+
47+
battery_state_broadcaster_spawner = Node(
48+
package="controller_manager",
49+
executable="spawner",
50+
arguments=["battery_state_broadcaster"]
51+
52+
Topics
53+
---------------------------------
54+
The battery state is published on ``~/battery_state``.
55+
Since it's a plugin within the controller manager, add a remapping of the form ``("~/battery_state", "/my_battery_state")`` to the *controller manager*, not the spawner, to change the topic name.

0 commit comments

Comments
 (0)