diff --git a/homer_nav_libs/CMakeLists.txt b/homer_nav_libs/CMakeLists.txt index 4bdc2491d461643f22cdd18c81d40612ca204c54..9d4962b2ea7715ece1475f65d870258114a572fe 100644 --- a/homer_nav_libs/CMakeLists.txt +++ b/homer_nav_libs/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 2.8.3) project(homer_nav_libs) +set(CMAKE_BUILD_TYPE Release) + find_package(catkin REQUIRED COMPONENTS roscpp geometry_msgs diff --git a/homer_nav_libs/src/Explorer/Explorer.cpp b/homer_nav_libs/src/Explorer/Explorer.cpp index 509964e423c1d73b88f62504bddfa3c7f200aa52..e57d72266ad0c9fef0db4ec816a3f5ccbf72a119 100644 --- a/homer_nav_libs/src/Explorer/Explorer.cpp +++ b/homer_nav_libs/src/Explorer/Explorer.cpp @@ -173,9 +173,9 @@ Eigen::Vector2i Explorer::getNearestAccessibleTarget(Eigen::Vector2i target ) ROS_INFO_STREAM("target cell in drivingdistancetransform: " << m_DrivingDistanceTransform->getValue ( target.x(), target.y() )); ROS_INFO_STREAM("target " << target << " is not approachable. Correcting target..."); int minSqrDist=INT_MAX; - for ( int x = 0; x < m_ObstacleTransform->height(); x++ ) + for ( int x = 0; x < m_ObstacleTransform->width(); x++ ) { - for ( int y = 0; y < m_ObstacleTransform->width(); y++ ) + for ( int y = 0; y < m_ObstacleTransform->height(); y++ ) { bool isSafe = m_ObstacleTransform->getValue ( x, y ) > m_FrontierSafenessFactor * m_MinAllowedObstacleDistance; if ( isApproachable ( x,y ) && isWalkable( x , y) && isSafe ) @@ -219,9 +219,9 @@ Eigen::Vector2i Explorer::getNearestWalkablePoint( Eigen::Vector2i target ) if ( !isWalkable( target.x(), target.y() ) ) { int minSqrDist=INT_MAX; - for ( int x = 0; x < m_ObstacleTransform->height(); x++ ) + for ( int x = 0; x < m_ObstacleTransform->width(); x++ ) { - for ( int y = 0; y < m_ObstacleTransform->width(); y++ ) + for ( int y = 0; y < m_ObstacleTransform->height(); y++ ) { if ( isWalkable ( x,y ) ) { diff --git a/homer_navigation/src/homer_navigation_node.cpp b/homer_navigation/src/homer_navigation_node.cpp index 11c740c466160dd8f730a57d9e4aaab8a6f6947c..976bf007651cf6db0539c3ac084b39b6e83bf24c 100644 --- a/homer_navigation/src/homer_navigation_node.cpp +++ b/homer_navigation/src/homer_navigation_node.cpp @@ -208,7 +208,7 @@ void HomerNavigationNode::calculatePath() { m_path_reaches_target = true; return; } - m_explorer->setOccupancyMap(m_width, m_width, m_origin, + m_explorer->setOccupancyMap(m_width, m_height, m_origin, &(*m_last_map_data)[0]); m_explorer->setStart( map_tools::toMapCoords(m_robot_pose.position, m_origin, m_resolution)); @@ -271,7 +271,7 @@ void HomerNavigationNode::startNavigation() { maskMap(); } - m_explorer->setOccupancyMap(m_width, m_width, m_origin, + m_explorer->setOccupancyMap(m_width, m_height, m_origin, &(*m_last_map_data)[0]); // check if there still exists a path to the original target @@ -896,10 +896,10 @@ void HomerNavigationNode::refreshParamsCallback( void HomerNavigationNode::mapCallback( const nav_msgs::OccupancyGrid::ConstPtr& msg) { - if (msg->info.height != msg->info.width) { - ROS_ERROR_STREAM("Incoming Map not quadratic. No map update!"); - return; - } + //if (msg->info.height != msg->info.width) { + //ROS_ERROR_STREAM("Incoming Map not quadratic. No map update!"); + //return; + //} if (m_last_map_data) { delete m_last_map_data; }