SMACC2
Loading...
Searching...
No Matches
cp_costmap_switch.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
22#include <array>
23#include <functional>
24#include <map>
25#include <memory>
26#include <string>
27
28#include <rclcpp/rclcpp.hpp>
29
31#include <smacc2/component.hpp>
32
33// #include <dynamic_reconfigure/DoubleParameter.h>
34// #include <dynamic_reconfigure/Reconfigure.h>
35// #include <dynamic_reconfigure/Config.h>
36
37namespace cl_nav2z
38{
39class CostmapProxy;
40
42{
43public:
44 enum class StandardLayers
45 {
50 };
51
52 static std::array<std::string, 4> layerNames;
53
55
56 void onInitialize() override;
57
58 static std::string getStandardCostmapName(StandardLayers layertype);
59
60 bool exists(std::string layerName);
61
62 void enable(std::string layerName);
63
64 void enable(StandardLayers layerType);
65
66 void disable(std::string layerName);
67
68 void disable(StandardLayers layerType);
69
71 std::string costmapName, std::string enablePropertyName = "enabled");
72
73private:
74 std::map<std::string, std::shared_ptr<CostmapProxy>> costmapProxies;
76};
77//-------------------------------------------------------------------------
79{
80public:
82 std::string costmap_name, std::string enablePropertyName, rclcpp::Node::SharedPtr nh);
83
84 void setCostmapEnabled(bool value);
85
86private:
87 std::string costmapName_;
88 rclcpp::Node::SharedPtr nh_;
89
90 inline rclcpp::Node::SharedPtr getNode() { return nh_; }
91};
92} // namespace cl_nav2z
void setCostmapEnabled(bool value)
rclcpp::Node::SharedPtr nh_
rclcpp::Node::SharedPtr getNode()
bool exists(std::string layerName)
cl_nav2z::ClNav2Z * nav2zClient_
static std::array< std::string, 4 > layerNames
static std::string getStandardCostmapName(StandardLayers layertype)
void disable(std::string layerName)
void registerProxyFromDynamicReconfigureServer(std::string costmapName, std::string enablePropertyName="enabled")
void enable(std::string layerName)
std::map< std::string, std::shared_ptr< CostmapProxy > > costmapProxies