moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
44
46{
47namespace
48{
49rclcpp::Logger getLogger()
50{
51 return moveit::getLogger("moveit.ros.occupancy_map_updater");
52}
53} // namespace
54
55OccupancyMapUpdater::OccupancyMapUpdater(const std::string& type) : type_(type)
56{
57}
58
60
62{
63 monitor_ = monitor;
64 tree_ = monitor->getOcTreePtr();
65}
66
67// TODO rework this function
68// void OccupancyMapUpdater::readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, double* value)
69// {
70// if (params.hasMember(param_name))
71// {
72// if (params[param_name].getType() == XmlRpc::XmlRpcValue::TypeInt)
73// *value = static_cast<int>(params[param_name]);
74// else
75// *value = static_cast<double>(params[param_name]);
76// }
77// }
78
79// TODO rework this function
80// void OccupancyMapUpdater::readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, unsigned int*
81// value)
82// {
83// if (params.hasMember(param_name))
84// *value = static_cast<int>(params[param_name]);
85// }
86
87bool OccupancyMapUpdater::updateTransformCache(const std::string& target_frame, const rclcpp::Time& target_time)
88{
89 transform_cache_.clear();
91 {
92 bool success = transform_provider_callback_(target_frame, target_time, transform_cache_);
93 if (!success)
94 {
95 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
96#pragma GCC diagnostic push
97#pragma GCC diagnostic ignored "-Wold-style-cast"
98 RCLCPP_ERROR_THROTTLE(
99 getLogger(), steady_clock, 1000,
100 "Transform cache was not updated. Self-filtering may fail. If transforms were not available yet, consider "
101 "setting robot_description_planning.shape_transform_cache_lookup_wait_time to wait longer for transforms");
102#pragma GCC diagnostic pop
103 }
104 return success;
105 }
106 else
107 {
108 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
109#pragma GCC diagnostic push
110#pragma GCC diagnostic ignored "-Wold-style-cast"
111 RCLCPP_WARN_THROTTLE(getLogger(), steady_clock, 1000,
112 "No callback provided for updating the transform cache for octomap updaters");
113#pragma GCC diagnostic pop
114 return false;
115 }
116}
117} // 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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79