Skip to content

Commit

Permalink
Fixed Styling
Browse files Browse the repository at this point in the history
Signed-off-by: Jatin Patil <[email protected]>
  • Loading branch information
JatinPatil2003 committed Jul 21, 2024
1 parent ad8b33f commit c595a11
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 18 deletions.
10 changes: 4 additions & 6 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
// Service to get the cost at a point
get_cost_service_ = create_service<nav2_msgs::srv::GetCost>(
"get_cost_" + getName(),
std::bind(&Costmap2DROS::getCostCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
std::bind(&Costmap2DROS::getCostCallback, this, std::placeholders::_1, std::placeholders::_2,
std::placeholders::_3));

// Add cleaning service
clear_costmap_service_ = std::make_unique<ClearCostmapService>(shared_from_this(), *this);
Expand Down Expand Up @@ -833,14 +834,11 @@ void Costmap2DROS::getCostCallback(
auto costmap = layered_costmap_->getCostmap();

unsigned int mx, my;
if (costmap->worldToMap(request->x, request->y, mx, my))
{
if (costmap->worldToMap(request->x, request->y, mx, my)) {
// Get the cost at the map coordinates
auto cost = static_cast<float>(costmap->getCost(mx, my));
response->cost = cost;
}
else
{
} else {
RCLCPP_WARN(get_logger(), "Point (%f, %f) is out of bounds", request->x, request->y);
response->cost = -1.0;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace nav2_rviz_plugins
{
class CostmapCostTool : public rviz_common::Tool
{
Q_OBJECT
Q_OBJECT
public:
CostmapCostTool();
virtual ~CostmapCostTool();
Expand All @@ -33,14 +33,14 @@ Q_OBJECT
void activate() override;
void deactivate() override;

int processMouseEvent( rviz_common::ViewportMouseEvent& event ) override;
int processMouseEvent(rviz_common::ViewportMouseEvent& event) override;

void callCostService(float x, float y);

void handleLocalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture);
void handleGlobalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture);

private Q_SLOTS:
private Q_SLOTS:
void updateAutoDeactivate();

private:
Expand All @@ -57,4 +57,4 @@ private Q_SLOTS:
};
}

#endif
#endif
22 changes: 14 additions & 8 deletions nav2_rviz_plugins/src/costmap_cost_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace nav2_rviz_plugins
CostmapCostTool::CostmapCostTool()
: qos_profile_(5)
{
shortcut_key_ = 'm';
shortcut_key_ = 'm';

auto_deactivate_property_ = new rviz_common::properties::BoolProperty(
"Single click", true,
Expand All @@ -44,14 +44,16 @@ void CostmapCostTool::onInitialize()
setIcon(rviz_common::loadPixmap("package://rviz_default_plugins/icons/classes/PointStamped.png"));

node_ = context_->getRosNodeAbstraction().lock()->get_raw_node();
local_cost_client_ = node_->create_client<nav2_msgs::srv::GetCost>("/local_costmap/get_cost_local_costmap");
global_cost_client_ = node_->create_client<nav2_msgs::srv::GetCost>("/global_costmap/get_cost_global_costmap");
local_cost_client_ =
node_->create_client<nav2_msgs::srv::GetCost>("/local_costmap/get_cost_local_costmap");
global_cost_client_ =
node_->create_client<nav2_msgs::srv::GetCost>("/global_costmap/get_cost_global_costmap");
}

void CostmapCostTool::activate() {}
void CostmapCostTool::deactivate() {}

int CostmapCostTool::processMouseEvent(rviz_common::ViewportMouseEvent& event)
int CostmapCostTool::processMouseEvent(rviz_common::ViewportMouseEvent & event)
{
int flags = 0;

Expand Down Expand Up @@ -95,18 +97,21 @@ void CostmapCostTool::callCostService(float x, float y)
return;
}

local_cost_client_->async_send_request(request, std::bind(&CostmapCostTool::handleLocalCostResponse, this, std::placeholders::_1));
local_cost_client_->async_send_request(request,
std::bind(&CostmapCostTool::handleLocalCostResponse, this, std::placeholders::_1));

// Call global costmap service
if (!global_cost_client_->wait_for_service(std::chrono::seconds(1))) {
RCLCPP_ERROR(node_->get_logger(), "Global costmap service not available");
return;
}

global_cost_client_->async_send_request(request, std::bind(&CostmapCostTool::handleGlobalCostResponse, this, std::placeholders::_1));
global_cost_client_->async_send_request(request,
std::bind(&CostmapCostTool::handleGlobalCostResponse, this, std::placeholders::_1));
}

void CostmapCostTool::handleLocalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture future)
void CostmapCostTool::handleLocalCostResponse(
rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture future)
{
auto response = future.get();
if (response->cost != -1) {
Expand All @@ -116,7 +121,8 @@ void CostmapCostTool::handleLocalCostResponse(rclcpp::Client<nav2_msgs::srv::Get
}
}

void CostmapCostTool::handleGlobalCostResponse(rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture future)
void CostmapCostTool::handleGlobalCostResponse(
rclcpp::Client<nav2_msgs::srv::GetCost>::SharedFuture future)
{
auto response = future.get();
if (response->cost != -1) {
Expand Down

0 comments on commit c595a11

Please sign in to comment.