41 #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp"
45 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
46 #include "geometry_msgs/msg/point_stamped.hpp"
52 : filter_info_topic_(
""), mask_topic_(
"")
64 rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock();
66 throw std::runtime_error{
"Failed to lock node"};
76 node->get_parameter(name_ +
"." +
"enabled", enabled_);
77 filter_info_topic_ = node->get_parameter(name_ +
"." +
"filter_info_topic").as_string();
78 double transform_tolerance {};
79 node->get_parameter(name_ +
"." +
"transform_tolerance", transform_tolerance);
84 name_ +
"/toggle_filter",
87 std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
88 }
catch (
const std::exception & ex) {
89 RCLCPP_ERROR(logger_,
"Parameter problem: %s", ex.what());
112 double robot_x,
double robot_y,
double robot_yaw,
113 double * ,
double * ,
double * ,
double * )
119 latest_pose_.x = robot_x;
120 latest_pose_.y = robot_y;
121 latest_pose_.theta = robot_yaw;
126 int min_i,
int min_j,
int max_i,
int max_j)
132 process(master_grid, min_i, min_j, max_i, max_j, latest_pose_);
137 const std::shared_ptr<rmw_request_id_t>,
138 const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
139 std::shared_ptr<std_srvs::srv::SetBool::Response> response)
141 enabled_ = request->data;
142 response->success =
true;
144 response->message =
"Enabled";
146 response->message =
"Disabled";
151 const std::string global_frame,
152 const geometry_msgs::msg::Pose2D & global_pose,
153 const std::string mask_frame,
154 geometry_msgs::msg::Pose2D & mask_pose)
const
156 if (mask_frame != global_frame) {
160 geometry_msgs::msg::TransformStamped transform;
161 geometry_msgs::msg::PointStamped in, out;
162 in.header.stamp = clock_->now();
163 in.header.frame_id = global_frame;
164 in.point.x = global_pose.x;
165 in.point.y = global_pose.y;
170 }
catch (tf2::TransformException & ex) {
173 "CostmapFilter: failed to get costmap frame (%s) "
174 "transformation to mask frame (%s) with error: %s",
175 global_frame.c_str(), mask_frame.c_str(), ex.what());
178 mask_pose.x = out.point.x;
179 mask_pose.y = out.point.y;
183 mask_pose = global_pose;
190 nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask,
191 double wx,
double wy,
unsigned int & mx,
unsigned int & my)
const
193 const double origin_x = filter_mask->info.origin.position.x;
194 const double origin_y = filter_mask->info.origin.position.y;
195 const double resolution = filter_mask->info.resolution;
196 const unsigned int size_x = filter_mask->info.width;
197 const unsigned int size_y = filter_mask->info.height;
199 if (wx < origin_x || wy < origin_y) {
203 mx =
static_cast<unsigned int>((wx - origin_x) / resolution);
204 my =
static_cast<unsigned int>((wy - origin_y) / resolution);
205 if (mx >= size_x || my >= size_y) {
A 2D costmap provides a mapping between points in the world and their associated "costs".
void activate() final
Activate the layer.
std::recursive_mutex mutex_t
: Provide a typedef to ease future code maintenance
void deactivate() final
Deactivate the layer.
bool worldToMask(nav_msgs::msg::OccupancyGrid::ConstSharedPtr filter_mask, double wx, double wy, unsigned int &mx, unsigned int &my) const
: Convert from world coordinates to mask coordinates. Similar to Costmap2D::worldToMap() method but w...
virtual void process(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j, const geometry_msgs::msg::Pose2D &pose)=0
: An algorithm for how to use that map's information. Fills the Costmap2D with calculated data and ma...
void reset() final
Reset the layer.
void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) final
Update the bounds of the master costmap by this layer's update dimensions.
bool transformPose(const std::string global_frame, const geometry_msgs::msg::Pose2D &global_pose, const std::string mask_frame, geometry_msgs::msg::Pose2D &mask_pose) const
: Transforms robot pose from current layer frame to mask frame
virtual void initializeFilter(const std::string &filter_info_topic)=0
: Initializes costmap filter. Creates subscriptions to filter-related topics
CostmapFilter()
A constructor.
void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) final
Update the costs in the master costmap in the window.
std::string filter_info_topic_
: Name of costmap filter info topic
rclcpp::Service< std_srvs::srv::SetBool >::SharedPtr enable_service_
: A service to enable/disable costmap filter
virtual void resetFilter()=0
: Resets costmap filter. Stops all subscriptions
tf2::Duration transform_tolerance_
: mask_frame_->global_frame_ transform tolerance
void onInitialize() final
Initialization process of layer on startup.
void enableCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::SetBool::Request > request, std::shared_ptr< std_srvs::srv::SetBool::Response > response)
Costmap filter enabling/disabling callback.
~CostmapFilter()
A destructor.
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.