Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use weak_ptr to avoid circular dependency in panther_battery package #310

Merged
merged 4 commits into from
May 27, 2024
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions panther_battery/include/panther_battery/battery_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,12 +49,16 @@ class BatteryPublisher
virtual void DiagnoseErrors(diagnostic_updater::DiagnosticStatusWrapper & status) = 0;
virtual void DiagnoseStatus(diagnostic_updater::DiagnosticStatusWrapper & status) = 0;

bool TimeoutReached() const;
void BatteryStatusLogger(const BatteryStateMsg & battery_state) const;
bool TimeoutReached();
void BatteryStatusLogger(const BatteryStateMsg & battery_state);
bool ChargerConnected() const;
std::string MapPowerSupplyStatusToString(uint8_t power_supply_status) const;

rclcpp::Node::SharedPtr node_;
rclcpp::Logger GetLogger();
rclcpp::Clock::SharedPtr GetClock();

// Use weak pointer to prevent circular dependency
rclcpp::Node::WeakPtr node_;
Copy link
Contributor

Choose a reason for hiding this comment

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

Maybe add info to do not forget why is that?

std::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;

private:
Expand Down
38 changes: 27 additions & 11 deletions panther_battery/src/battery_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,13 @@ BatteryPublisher::BatteryPublisher(
const std::shared_ptr<diagnostic_updater::Updater> & diagnostic_updater)
: node_(std::move(node)), diagnostic_updater_(std::move(diagnostic_updater))
{
node_->declare_parameter<float>("battery_timeout", 1.0);
battery_timeout_ = node_->get_parameter("battery_timeout").as_double();
node->declare_parameter<float>("battery_timeout", 1.0);
battery_timeout_ = node->get_parameter("battery_timeout").as_double();

charger_connected_ = false;
last_battery_info_time_ = rclcpp::Time(std::int64_t(0), RCL_ROS_TIME);

io_state_sub_ = node_->create_subscription<IOStateMsg>(
io_state_sub_ = node->create_subscription<IOStateMsg>(
"hardware/io_state", 3,
[&](const IOStateMsg::SharedPtr msg) { charger_connected_ = msg->charger_connected; });

Expand All @@ -47,10 +47,10 @@ void BatteryPublisher::Publish()
{
try {
this->Update();
last_battery_info_time_ = node_->get_clock()->now();
last_battery_info_time_ = GetClock()->now();
} catch (const std::runtime_error & e) {
RCLCPP_ERROR_STREAM_THROTTLE(
node_->get_logger(), *node_->get_clock(), 1000, "Error reading battery data: " << e.what());
GetLogger(), *GetClock(), 1000, "Error reading battery data: " << e.what());

diagnostic_updater_->broadcast(
diagnostic_msgs::msg::DiagnosticStatus::ERROR,
Expand All @@ -65,13 +65,13 @@ void BatteryPublisher::Publish()
this->LogErrors();
}

bool BatteryPublisher::TimeoutReached() const
bool BatteryPublisher::TimeoutReached()
{
return (node_->get_clock()->now() - last_battery_info_time_) >
return (GetClock()->now() - last_battery_info_time_) >
rclcpp::Duration::from_seconds(battery_timeout_);
}

void BatteryPublisher::BatteryStatusLogger(const BatteryStateMsg & battery_state) const
void BatteryPublisher::BatteryStatusLogger(const BatteryStateMsg & battery_state)
{
std::string msg{};

Expand All @@ -81,20 +81,20 @@ void BatteryPublisher::BatteryStatusLogger(const BatteryStateMsg & battery_state
"The charger has been plugged in, but the charging process has not started. Check if the "
"charger is connected to a power source.";

RCLCPP_WARN_STREAM_THROTTLE(node_->get_logger(), *node_->get_clock(), 10000, msg);
RCLCPP_WARN_STREAM_THROTTLE(GetLogger(), *GetClock(), 10000, msg);
break;

case BatteryStateMsg::POWER_SUPPLY_STATUS_CHARGING:
msg = "The robot is charging. Current battery percentage: " +
std::to_string(static_cast<int>(round(battery_state.percentage * 100.0))) + "%.";

RCLCPP_INFO_STREAM_THROTTLE(node_->get_logger(), *node_->get_clock(), 180000, msg);
RCLCPP_INFO_STREAM_THROTTLE(GetLogger(), *GetClock(), 180000, msg);
break;

case BatteryStateMsg::POWER_SUPPLY_STATUS_FULL:
msg = "The battery is fully charged. Robot can be disconnected from the charger.";

RCLCPP_INFO_STREAM_THROTTLE(node_->get_logger(), *node_->get_clock(), 180000, msg);
RCLCPP_INFO_STREAM_THROTTLE(GetLogger(), *GetClock(), 180000, msg);
break;

default:
Expand Down Expand Up @@ -122,4 +122,20 @@ std::string BatteryPublisher::MapPowerSupplyStatusToString(uint8_t power_supply_
}
}

rclcpp::Logger BatteryPublisher::GetLogger()
{
if (auto node = node_.lock()) {
return node->get_logger();
}
return rclcpp::get_logger("battery_publisher");
}

rclcpp::Clock::SharedPtr BatteryPublisher::GetClock()
{
if (auto node = node_.lock()) {
return node->get_clock();
}
return std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
}

} // namespace panther_battery
16 changes: 7 additions & 9 deletions panther_battery/src/dual_battery_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,21 +38,21 @@ DualBatteryPublisher::DualBatteryPublisher(
battery_1_(std::move(battery_1)),
battery_2_(std::move(battery_2))
{
battery_pub_ = node_->create_publisher<BatteryStateMsg>("battery", 5);
battery_1_pub_ = node_->create_publisher<BatteryStateMsg>("battery_1_raw", 5);
battery_2_pub_ = node_->create_publisher<BatteryStateMsg>("battery_2_raw", 5);
battery_pub_ = node->create_publisher<BatteryStateMsg>("battery", 5);
battery_1_pub_ = node->create_publisher<BatteryStateMsg>("battery_1_raw", 5);
battery_2_pub_ = node->create_publisher<BatteryStateMsg>("battery_2_raw", 5);
}

void DualBatteryPublisher::Update()
{
const auto header_stamp = node_->get_clock()->now();
const auto header_stamp = this->GetClock()->now();
battery_1_->Update(header_stamp, ChargerConnected());
battery_2_->Update(header_stamp, ChargerConnected());
}

void DualBatteryPublisher::Reset()
{
const auto header_stamp = node_->get_clock()->now();
const auto header_stamp = this->GetClock()->now();
battery_1_->Reset(header_stamp);
battery_2_->Reset(header_stamp);
}
Expand All @@ -71,13 +71,11 @@ void DualBatteryPublisher::LogErrors()
{
if (battery_1_->HasErrorMsg()) {
RCLCPP_ERROR_STREAM_THROTTLE(
node_->get_logger(), *node_->get_clock(), 10000,
"Battery nr 1 error: " << battery_1_->GetErrorMsg());
GetLogger(), *GetClock(), 10000, "Battery nr 1 error: " << battery_1_->GetErrorMsg());
}
if (battery_2_->HasErrorMsg()) {
RCLCPP_ERROR_STREAM_THROTTLE(
node_->get_logger(), *node_->get_clock(), 10000,
"Battery nr 2 error: " << battery_2_->GetErrorMsg());
GetLogger(), *GetClock(), 10000, "Battery nr 2 error: " << battery_2_->GetErrorMsg());
}
}

Expand Down
11 changes: 5 additions & 6 deletions panther_battery/src/single_battery_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,19 +35,19 @@ SingleBatteryPublisher::SingleBatteryPublisher(
const std::shared_ptr<Battery> & battery)
: BatteryPublisher(std::move(node), std::move(diagnostic_updater)), battery_(std::move(battery))
{
battery_pub_ = node_->create_publisher<BatteryStateMsg>("battery", 5);
battery_1_pub_ = node_->create_publisher<BatteryStateMsg>("battery_1_raw", 5);
battery_pub_ = node->create_publisher<BatteryStateMsg>("battery", 5);
battery_1_pub_ = node->create_publisher<BatteryStateMsg>("battery_1_raw", 5);
}

void SingleBatteryPublisher::Update()
{
const auto header_stamp = node_->get_clock()->now();
const auto header_stamp = this->GetClock()->now();
battery_->Update(header_stamp, ChargerConnected());
}

void SingleBatteryPublisher::Reset()
{
const auto header_stamp = node_->get_clock()->now();
const auto header_stamp = this->GetClock()->now();
battery_->Reset(header_stamp);
}

Expand All @@ -63,8 +63,7 @@ void SingleBatteryPublisher::LogErrors()
{
if (battery_->HasErrorMsg()) {
RCLCPP_ERROR_STREAM_THROTTLE(
node_->get_logger(), *node_->get_clock(), 10000,
"Battery error: " << battery_->GetErrorMsg());
GetLogger(), *GetClock(), 10000, "Battery error: " << battery_->GetErrorMsg());
}
}

Expand Down