moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
occupancy_map_updater.h
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan, Jon Binney */
36
37#pragma once
38
41
42#include <geometric_shapes/shapes.h>
43#include <rclcpp/rclcpp.hpp>
44
45#include <Eigen/Core>
46#include <Eigen/Geometry>
47
48#include <map>
49#include <string>
50#include <functional>
51
53{
54using ShapeHandle = unsigned int;
55using ShapeTransformCache = std::map<ShapeHandle, Eigen::Isometry3d, std::less<ShapeHandle>,
56 Eigen::aligned_allocator<std::pair<const ShapeHandle, Eigen::Isometry3d> > >;
57using TransformCacheProvider = std::function<bool(const std::string&, const rclcpp::Time&, ShapeTransformCache&)>;
58
60
61MOVEIT_CLASS_FORWARD(OccupancyMapUpdater); // Defines OccupancyMapUpdaterPtr, ConstPtr, WeakPtr... etc
62
66{
67public:
68 OccupancyMapUpdater(const std::string& type);
70
72 void setMonitor(OccupancyMapMonitor* monitor);
73
76 virtual bool setParams(const std::string& name_space) = 0;
77
80 virtual bool initialize(const rclcpp::Node::SharedPtr& node) = 0;
81
82 virtual void start() = 0;
83
84 virtual void stop() = 0;
85
86 virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) = 0;
87
88 virtual void forgetShape(ShapeHandle handle) = 0;
89
90 const std::string& getType() const
91 {
92 return type_;
93 }
94
95 void setTransformCacheCallback(const TransformCacheProvider& transform_callback)
96 {
97 transform_provider_callback_ = transform_callback;
98 }
99
101 {
102 debug_info_ = flag;
103 }
104
105protected:
107 std::string type_;
112
113 bool updateTransformCache(const std::string& target_frame, const rclcpp::Time& target_time);
114
115 // TODO rework this function
116 // static void readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, double* value);
117 // static void readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, unsigned int* value);
118};
119} // namespace occupancy_map_monitor
#define MOVEIT_CLASS_FORWARD(C)
Base class for classes which update the occupancy map.
virtual bool initialize(const rclcpp::Node::SharedPtr &node)=0
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
virtual void forgetShape(ShapeHandle handle)=0
void setTransformCacheCallback(const TransformCacheProvider &transform_callback)
collision_detection::OccMapTreePtr tree_
virtual ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)=0
virtual bool setParams(const std::string &name_space)=0
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
void setMonitor(OccupancyMapMonitor *monitor)
This is the first function to be called after construction.
std::shared_ptr< OccMapTree > OccMapTreePtr
std::function< bool(const std::string &, const rclcpp::Time &, ShapeTransformCache &)> TransformCacheProvider
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache