Skip to content

Conversation

YaraShahin
Copy link

@YaraShahin YaraShahin commented Sep 5, 2025

This Pull Request introduces the Battery State Broadcaster, a controller for publishing battery status information in ROS2. The broadcaster reads battery-related state interfaces from hardware and exposes them in standardized ROS messages for easy integration with monitoring tools, logging systems, and higher-level decision-making nodes.

Dependency: This PR depends on control_msgs#250 which introduces the BatteryStates message.

Features

  • Aggregated and Raw Outputs:

    • Publishes a combined sensor_msgs::msg::BatteryState message representing the overall system status.

    • Publishes per-joint control_msgs::msg::BatteryStates messages containing raw values.

  • Flexible Interface Support: Reads from interfaces such as battery_voltage, battery_current, battery_temperature, battery_charge, battery_percentage, and others.

  • Parameterization: Configurable through YAML using generate_parameter_library.

Interfaces

Published Topics

  • ~/battery_state (sensor_msgs::msg::BatteryState) — aggregated battery status across all configured joints.

  • ~/raw_battery_states (control_msgs::msg::BatteryStates) — raw per-joint battery state values.

Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that:

  1. Limited scope. Your PR should do one thing or one set of things. Avoid adding “random fixes” to PRs. Put those on separate PRs.
  2. Give your PR a descriptive title. Add a short summary, if required.
  3. Make sure the pipeline is green.
  4. Don’t be afraid to request reviews from maintainers.
  5. New code = new tests. If you are adding new functionality, always make sure to add some tests exercising the code and serving as live documentation of your original intention.

To send us a pull request, please:

  • Fork the repository.
  • Modify the source; please focus on the specific change you are contributing. If you also reformat all the code, it will be hard for us to focus on your change.
  • Ensure local tests pass. (colcon test and pre-commit run (requires you to install pre-commit by pip3 install pre-commit)
  • Commit to your fork using clear commit messages.
  • Send a pull request, answering any default questions in the pull request interface.
  • Pay attention to any automated CI failures reported in the pull request, and stay involved in the conversation.

Copy link
Contributor

@christophfroehlich christophfroehlich left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for your contribution.
Unfortunately, there is already an existing package with this name.
https://index.ros.org/p/battery_state_broadcaster/#rolling

Can you please highlight the difference between yours and the existing one? If there is a benefit, we could either rename yours or ask the maintainers/authors of the original one to move it to our repository and merge your additions on top. As an alternative, you could also open a PR there.

Comment on lines 9 to 15
<maintainer email="[email protected]">Dr. Denis Štogl</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

please use the usual set of maintainers here from other packages

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

Comment on lines 21 to 22
<build_depend>sensor_msgs</build_depend>
<build_depend>control_msgs</build_depend>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

anything you find in "build_depend" and also "exec_depend", it could be shortened to just a single "depend" entry

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

Comment on lines 93 to 94
float get_or_nan(int interface_cnt);
char get_or_unknown(int interface_cnt);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

please make sure that the return type from these align with where and how you use them. Internally we use doubles for a lot of stuff, using float may cause a narrowing conversion.

for char, I see you used uint8_t below. If that is what you are looking for, I suggest using that here as return type too.

Also please double check if the windows compilation (probably on the Ci is enough) is fine with the uint8_t type or maybe you need to include stdint.h

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for pointing this out. I mainly have to do these conversions to match the types of the BatteryState msg which uses float and int8.

Regarding your suggestions:

  • For get_or_nan, I now use value_or with a cast to float, so the internal double stays until assignment to the message field:
static_cast<float>(state_interfaces_[interface_cnt].get_optional<double>().value_or(kUninitializedValue));
  • For get_or_unknown, I cast to uint8_t instead of char:
static_cast<uint8_t>(state_interfaces_[interface_cnt].get_optional<double>().value_or(
            sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN));
  • Replaced all char by uint8_t

  • Since other broadcasters are also using uint8_t, I believe it should be fine. I added the <cstdint> anyways for safety.

This should keep the double type used by ros2 control till the end where it has to be assigned to the float/int8 message field.


std::vector<bool> battery_presence_;

private:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I bet some of the above could be moved to the private section ;)

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just moved what I could to private; unfortunately I am using some of them in test so they have to stay protected.

auto opt = state_interfaces_[interface_cnt].get_optional<double>();
if (opt.has_value())
{
return static_cast<float>(*opt);
Copy link
Member

@bmagyar bmagyar Sep 8, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
return static_cast<float>(*opt);
return opt->value();

I won't highlight all of them, please fix the rest of the static_casts

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed as mentioned in the comment above. Thanks for the tip!

{
return static_cast<char>(*opt);
}
return 0;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd think a little more carefully about this. What does return 0; mean in the scope of a char? I understand how it works in the number-crunching way of computers and bytes but what does it tell us from a semantic perspective? How do you want to handle an error from here vs an actual 0 value?

Copy link
Author

@YaraShahin YaraShahin Oct 1, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For all the interfaces in which I was using this function, 0 was the enum value for UNKNOWN. So, that's its semantic value as well in case of an error.

After your recent comment, I changed this to

static_cast<uint8_t>(state_interfaces_[interface_cnt].get_optional<double>().value_or(
            sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN));

which illustrates this concept better.

Copy link
Member

@bmagyar bmagyar left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A few small cleanup steps, otherwise looks good!

@YaraShahin
Copy link
Author

YaraShahin commented Sep 9, 2025

Thank you for your contribution. Unfortunately, there is already an existing package with this name. https://index.ros.org/p/battery_state_broadcaster/#rolling

Can you please highlight the difference between yours and the existing one? If there is a benefit, we could either rename yours or ask the maintainers/authors of the original one to move it to our repository and merge your additions on top. As an alternative, you could also open a PR there.

Thank you @christophfroehlich for your feedback. I’ve reached out to the maintainer of the original battery_state_broadcaster package by email to discuss whether they intend to release it into ros2_controllers and how we could best align efforts.

In the meantime, I’ve prepared a summary of the differences and benefits of this implementation, as follows:

  • Full sensor_msgs::msg::BatteryState coverage:
    The existing broadcaster is currently focused on publishing the voltage interface with parameters for power_supply_technology and design_capacity. This version extends by also broadcasting additional BatteryState interfaces (current, charge, temperature, percentage, power_supply_status, power_supply_health, and presence), while filling the remaining fields via parameters.

  • Flexible parameterization: Provides per-joint parameters to enable or disable specific battery interfaces, making it adaptable to different hardware setups. It also supports parameters for fixed battery properties.

  • Multi-battery support: While the existing package is designed around a single battery, this version broadens usage to multi-battery systems, publishing both per-battery states and an aggregated battery state topic (control_msgs::msg::BatteryStates).

  • Battery analytics:
    Adds analytics features on top of the basic fields, including:

    • Percentage calculation (if no direct percentage interface is available) using voltage and min/max parameters.
    • Presence detection (via battery_present interface or inferred from voltage).
    • Aggregation across multiple batteries (averages, sums, and combined status/health).
  • Consistency with ros2_controllers style: Follows established controller/broadcaster structure, and documented best practices.

  • Test coverage: Includes unit tests aligned with the ros2_controllers testing style, ensuring reliability.

@ottojo
Copy link

ottojo commented Sep 9, 2025

Hi! Creator of https://github.com/ipa320/ros_battery_monitoring here! As already realized my package is pretty bare bones, and admittedly not in active use by us at the moment (in a previous robot we only had battery state information from the motor controller - now we have a dedicated package receiving CAN messages from the battery and publishing that as BatteryState).
There is a PR ipa320/ros_battery_monitoring#3 still open which adds more functionality to my package, but i have not had the time/priority to look at it. So i think leaving the entire topic to the ros2_control project seems reasonable.

I have only briefly skimmed over this PR, a technical question that i still have is: Is the battery state now coupled to joints? IIRC, i had one hardware interface plugin which implemented both the joint interfaces and the battery data interfaces as "sensor" tags beside the "joint"s in the XML. But maybe my setup is the one out of the ordinary here...

Anyways, i myself don't have an issue giving the battery_state_broadcaster package name to the ros2_control project, if thats the question, although i do wonder if anybody is using my package and will have their battery monitoring unexpectedly broken...

@christophfroehlich
Copy link
Contributor

Anyways, i myself don't have an issue giving the battery_state_broadcaster package name to the ros2_control project, if thats the question, although i do wonder if anybody is using my package and will have their battery monitoring unexpectedly broken...

Thanks for that offer. According to index.ros.org there is no released package dependent on it at least. I haven't checked if the new proposed broadcaster can be rewritten to support the existing broadcaster config? Maybe @YaraShahin can evaluate that. If this does not make sense, we can break it on rolling but leave the other distros as they are now.

@YaraShahin
Copy link
Author

YaraShahin commented Sep 9, 2025

I have only briefly skimmed over this PR, a technical question that i still have is: Is the battery state now coupled to joints? IIRC, i had one hardware interface plugin which implemented both the joint interfaces and the battery data interfaces as "sensor" tags beside the "joint"s in the XML. But maybe my setup is the one out of the ordinary here...

Thanks a lot @ottojo for your feedback 🙏

To your question: in our implementation the battery state is indeed exposed via state interfaces that are grouped under state_joints. This keeps it consistent with other broadcasters in ros2_control (IMU, force-torque, etc.), but it does mean batteries are defined alongside joints in the URDF. If I understand correctly, your case should still be supported, since you could list your sensor_name under state_joints parameter. The state interface exposed is the same in both cases, for example: <sensor-or-joint-name>/voltage.

I’ll also take a look at the differences between our current implementation and the PR you mentioned in your repo, to see if there’s anything we should carry over here.

Thanks again for the clarification and for being open to handing over the package name — we’ll make sure to handle the transition carefully so existing users aren’t left behind.

@YaraShahin
Copy link
Author

Thanks for that offer. According to index.ros.org there is no released package dependent on it at least. I haven't checked if the new proposed broadcaster can be rewritten to support the existing broadcaster config? Maybe @YaraShahin can evaluate that. If this does not make sense, we can break it on rolling but leave the other distros as they are now.

Thanks @christophfroehlich for checking the dependency situation. I’ll review whether the configuration style from ipa320/ros_battery_monitoring can be supported directly. If keeping full compatibility doesn’t make sense, then I’ll add a migration note in the docs for Rolling so existing users can adapt their configs.

@christophfroehlich
Copy link
Contributor

@YaraShahin any updates?

@YaraShahin
Copy link
Author

@YaraShahin any updates?

Thanks for the reminder, I’ll push the fixes this week.

@YaraShahin YaraShahin force-pushed the add-battery-state-broadcaster branch from d5255d9 to 860e8ea Compare September 30, 2025 22:51
@YaraShahin
Copy link
Author

A few small cleanup steps, otherwise looks good!

Thanks for the feedback! I’ve fixed the points you mentioned.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants