00001
00004
00005
00006
00007
00008 #include "../../include/cost_map_demos/from_ros_costmaps.hpp"
00009
00010
00011
00012
00013
00014 namespace cost_map_demos {
00015
00016
00017
00018
00019
00020 void broadcastCostmap2DROSTestSuiteTransforms(TransformBroadcaster& broadcaster) {
00021 broadcaster.add("base_link_5x5", tf::Vector3(1.0, 1.0, 0.0), tf::Quaternion(0, 0, 0, 1));
00022 broadcaster.add("base_link_4x4", tf::Vector3(1.0, -3.0, 0.0), tf::Quaternion(0, 0, 0, 1));
00023 broadcaster.add("base_link_5x5_3x3_offset", tf::Vector3(-3.7, 2.4, 0.0), tf::Quaternion(0, 0, 0, 1));
00024 broadcaster.add("base_link_5x5_3x3_centre", tf::Vector3(-3.5, -3.5, 0.0), tf::Quaternion(0, 0, 0, 1));
00025 broadcaster.add("base_link_5x5_2_5x2_5_offset", tf::Vector3(-9.7, 2.4, 0.0), tf::Quaternion(0, 0, 0, 1));
00026 broadcaster.startBroadCastingThread();
00027 }
00028
00029
00030
00031
00032
00033 ROSCostmapServer::ROSCostmapServer(const std::string& name,
00034 const std::string& base_link_transform_name,
00035 const cost_map::Position& origin,
00036 const double& width,
00037 const double& height
00038 )
00039 : transform_listener(ros::Duration(1.0))
00040 {
00041 ros::NodeHandle private_node_handle("~");
00042
00043
00044
00045
00046
00047 private_node_handle.setParam(name + "/robot_base_frame", base_link_transform_name);
00048 private_node_handle.setParam(name + "/origin_x", origin.x());
00049 private_node_handle.setParam(name + "/origin_y", origin.y());
00050 private_node_handle.setParam(name + "/width", width);
00051 private_node_handle.setParam(name + "/height", height);
00052 private_node_handle.setParam(name + "/plugins", std::vector<std::string>());
00053 private_node_handle.setParam(name + "/resolution", 0.5);
00054 private_node_handle.setParam(name + "/robot_radius", 0.03);
00055 costmap = std::make_shared<ROSCostmap>(name, transform_listener);
00056
00057 for ( unsigned int index = 0; index < costmap->getCostmap()->getSizeInCellsY(); ++index ) {
00058 unsigned int dimension = costmap->getCostmap()->getSizeInCellsX();
00059
00060
00061 for ( unsigned int fill_index = 0; fill_index < dimension - 2; ++fill_index )
00062 {
00063 double fraction = static_cast<double>(fill_index + 1) / static_cast<double>(costmap->getCostmap()->getSizeInCellsX());
00064 costmap->getCostmap()->setCost(fill_index, index, fraction*costmap_2d::INSCRIBED_INFLATED_OBSTACLE );
00065 }
00066 costmap->getCostmap()->setCost(dimension - 2, index, costmap_2d::LETHAL_OBSTACLE);
00067 costmap->getCostmap()->setCost(dimension - 1, index, costmap_2d::NO_INFORMATION);
00068 }
00069 }
00070
00071
00072
00073
00074
00075 }