moveit2
The MoveIt Motion Planning Framework for ROS 2.
occupancy_map_updater.cpp
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 
39 #include <rclcpp/clock.hpp>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <string>
43 
44 namespace occupancy_map_monitor
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.occupancy_map_updater");
47 
49 {
50 }
51 
53 
55 {
56  monitor_ = monitor;
57  tree_ = monitor->getOcTreePtr();
58 }
59 
60 // TODO rework this function
61 // void OccupancyMapUpdater::readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, double* value)
62 // {
63 // if (params.hasMember(param_name))
64 // {
65 // if (params[param_name].getType() == XmlRpc::XmlRpcValue::TypeInt)
66 // *value = static_cast<int>(params[param_name]);
67 // else
68 // *value = (double)params[param_name];
69 // }
70 // }
71 
72 // TODO rework this function
73 // void OccupancyMapUpdater::readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, unsigned int*
74 // value)
75 // {
76 // if (params.hasMember(param_name))
77 // *value = static_cast<int>(params[param_name]);
78 // }
79 
80 bool OccupancyMapUpdater::updateTransformCache(const std::string& target_frame, const rclcpp::Time& target_time)
81 {
82  transform_cache_.clear();
84  {
85  bool success = transform_provider_callback_(target_frame, target_time, transform_cache_);
86  if (!success)
87  {
88  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
89  RCLCPP_ERROR_THROTTLE(
90  LOGGER, steady_clock, 1000,
91  "Transform cache was not updated. Self-filtering may fail. If transforms were not available yet, consider "
92  "setting robot_description_planning.shape_transform_cache_lookup_wait_time to wait longer for transforms");
93  }
94  return success;
95  }
96  else
97  {
98  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
99  RCLCPP_WARN_THROTTLE(LOGGER, steady_clock, 1000,
100  "No callback provided for updating the transform cache for octomap updaters");
101  return false;
102  }
103 }
104 } // namespace occupancy_map_monitor
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
collision_detection::OccMapTreePtr tree_
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.
const rclcpp::Logger LOGGER
Definition: async_test.h:31