RAPP Platform  v0.6.0
RAPP Platform is a collection of ROS nodes and back-end processes that aim to deliver ready-to-use generic services to robots
 All Classes Namespaces Files Functions Variables Macros
rapp_static_layer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef RAPP_COSTMAP_2D_STATIC_LAYER_H_
39 #define RAPP_COSTMAP_2D_STATIC_LAYER_H_
40 
41 #include <ros/ros.h>
42 #include <ros/service_manager.h>
43 #include <costmap_2d/costmap_layer.h>
44 #include <costmap_2d/layered_costmap.h>
45 #include <costmap_2d/GenericPluginConfig.h>
46 #include <dynamic_reconfigure/server.h>
47 #include <nav_msgs/OccupancyGrid.h>
48 #include <nav_msgs/GetMap.h>
49 #include <map_msgs/OccupancyGridUpdate.h>
50 #include <message_filters/subscriber.h>
51 #include <memory>
52 #include <rapp_platform_ros_communications/Costmap2dRosSrv.h>
53 
54 namespace costmap_2d
55 {
56 
57 class RappStaticLayer : public CostmapLayer
58 {
59 public:
61  virtual ~RappStaticLayer();
62  virtual void onInitialize();
63  virtual void activate();
64  virtual void deactivate();
65  virtual void reset();
66 
67  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x,
68  double* max_y);
69  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
70 
71  virtual void matchSize();
72 
73 private:
80  void incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map);
81  void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update);
82  void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
83 bool incomingUpdateService( rapp_platform_ros_communications::Costmap2dRosSrvRequest& req,
84  rapp_platform_ros_communications::Costmap2dRosSrvResponse& res);
85  unsigned char interpretValue(unsigned char value);
86 
87  std::string global_frame_;
91  unsigned int x_,y_,width_,height_;
95  ros::Subscriber map_sub_, map_update_sub_;
96  ros::ServiceServer costmap_update_service;
98 
99  mutable boost::recursive_mutex lock_;
100  dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *dsrv_;
101 };
102 
103 } // namespace costmap_2d
104 
105 #endif // RAPP_COSTMAP_2D_STATIC_LAYER_H_
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
std::string global_frame_
The global frame for the costmap.
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
bool incomingUpdateService(rapp_platform_ros_communications::Costmap2dRosSrvRequest &req, rapp_platform_ros_communications::Costmap2dRosSrvResponse &res)
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
ros::ServiceServer costmap_update_service
boost::recursive_mutex lock_
unsigned char interpretValue(unsigned char value)
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_