Skip to content

Commit

Permalink
Feedback from review.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Aug 7, 2024
1 parent b67270f commit 864a450
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 1 deletion.
1 change: 0 additions & 1 deletion nav2_rviz_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,6 @@ target_link_libraries(${library_name} PUBLIC
${std_msgs_TARGETS}
tf2_geometry_msgs::tf2_geometry_msgs
${visualization_msgs_TARGETS}
# TODO(clalancette): We aren't linking against any Qt libraries here?
)
target_link_libraries(${library_name} PRIVATE
ament_index_cpp::ament_index_cpp
Expand Down
3 changes: 3 additions & 0 deletions nav2_rviz_plugins/src/costmap_cost_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@ void CostmapCostTool::onInitialize()
node_ptr_ = context_->getRosNodeAbstraction().lock();
if (node_ptr_ == nullptr) {
// The node no longer exists, so just don't initialize
RCLCPP_ERROR(
rclcpp::get_logger("costmap_cost_tool"),
"Underlying ROS node no longer exists, initialization failed");
return;
}
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
Expand Down
3 changes: 3 additions & 0 deletions nav2_rviz_plugins/src/docking_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,9 @@ void DockingPanel::onInitialize()
node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
if (node_ptr_ == nullptr) {
// The node no longer exists, so just don't initialize
RCLCPP_ERROR(
rclcpp::get_logger("docking_panel"),
"Underlying ROS node no longer exists, initialization failed");
return;
}
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
Expand Down
3 changes: 3 additions & 0 deletions nav2_rviz_plugins/src/nav2_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -781,6 +781,9 @@ Nav2Panel::onInitialize()
node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock();
if (node_ptr_ == nullptr) {
// The node no longer exists, so just don't initialize
RCLCPP_ERROR(
rclcpp::get_logger("nav2_panel"),
"Underlying ROS node no longer exists, initialization failed");
return;
}
rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node();
Expand Down

0 comments on commit 864a450

Please sign in to comment.