Skip to content
Snippets Groups Projects
Commit 911fad04 authored by Carl Delsey's avatar Carl Delsey Committed by bpwilcox
Browse files

Add getRobotPose service type.

parent c2517276
No related branches found
No related tags found
No related merge requests found
......@@ -17,6 +17,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Path.msg"
"msg/VoxelGrid.msg"
"srv/GetCostmap.srv"
"srv/GetRobotPose.srv"
"srv/ClearCostmapExceptRegion.srv"
"srv/ClearCostmapAroundRobot.srv"
"srv/ClearEntireCostmap.srv"
......
# Get the latest robot pose in the frame of the costmap
std_msgs/Empty request
---
geometry_msgs/PoseStamped pose
bool is_pose_valid
......@@ -23,23 +23,23 @@
namespace nav2_util
{
class CostmapServiceClient : public nav2_util::ServiceClient<nav2_msgs::srv::GetCostmap>
class CostmapServiceClient : public ServiceClient<nav2_msgs::srv::GetCostmap>
{
public:
explicit CostmapServiceClient(const std::string & parent_node_name)
: nav2_util::ServiceClient<nav2_msgs::srv::GetCostmap>("GetCostmap", parent_node_name)
: ServiceClient<nav2_msgs::srv::GetCostmap>("GetCostmap", parent_node_name)
{
}
explicit CostmapServiceClient(rclcpp::Node::SharedPtr node)
explicit CostmapServiceClient(rclcpp::Node::SharedPtr & node)
: ServiceClient<nav2_msgs::srv::GetCostmap>("GetCostmap", node)
{
}
using CostmapServiceRequest =
nav2_util::ServiceClient<nav2_msgs::srv::GetCostmap>::RequestType;
ServiceClient<nav2_msgs::srv::GetCostmap>::RequestType;
using CostmapServiceResponse =
nav2_util::ServiceClient<nav2_msgs::srv::GetCostmap>::ResponseType;
ServiceClient<nav2_msgs::srv::GetCostmap>::ResponseType;
};
} // namespace nav2_util
......
// Copyright (c) 2019 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef NAV2_UTIL__GET_ROBOT_POSE_CLIENT_HPP_
#define NAV2_UTIL__GET_ROBOT_POSE_CLIENT_HPP_
#include "nav2_util/service_client.hpp"
#include "nav2_msgs/srv/get_robot_pose.hpp"
namespace nav2_util
{
class GetRobotPoseClient : public ServiceClient<nav2_msgs::srv::GetRobotPose>
{
public:
explicit GetRobotPoseClient(const std::string & parent_node_name)
: ServiceClient<nav2_msgs::srv::GetRobotPose>("GetRobotPose", parent_node_name)
{
}
explicit GetRobotPoseClient(rclcpp::Node::SharedPtr & node)
: ServiceClient<nav2_msgs::srv::GetRobotPose>("GetRobotPose", node)
{
}
using GetRobotPoseRequest =
ServiceClient<nav2_msgs::srv::GetRobotPose>::RequestType;
using GetRobotPoseResponse =
ServiceClient<nav2_msgs::srv::GetRobotPose>::ResponseType;
};
} // namespace nav2_tasks
#endif // NAV2_UTIL__GET_ROBOT_POSE_CLIENT_HPP_
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment