diff --git a/README.txt b/README.txt index 42580914..98927dbb 100644 --- a/README.txt +++ b/README.txt @@ -1,15 +1,3 @@ -== Postprocessing Logfile example == -Download this file: -http://code.google.com/p/tu-darmstadt-ros-pkg/downloads/detail?name=Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag&can=2&q= - -Open a new terminal window, type: -rosmake hector_slam - -Launch the tutorial launch file provided in the hector_slam_launch package: -roslaunch hector_slam_launch tutorial.launch - -Open another terminal, enter the directory of the .bag file and type: -rosbag play Team_Hector_MappingBox_RoboCup_2011_Rescue_Arena.bag --clock - -You should now be able see the mapping process in rviz. +# hector_slam +See the ROS Wiki for documentation: http://wiki.ros.org/hector_slam diff --git a/hector_compressed_map_transport/CHANGELOG.rst b/hector_compressed_map_transport/CHANGELOG.rst index c7473082..9d52cbba 100644 --- a/hector_compressed_map_transport/CHANGELOG.rst +++ b/hector_compressed_map_transport/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hector_compressed_map_transport ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ +* Use the FindEigen3.cmake module provided by Eigen +* Contributors: Johannes Meyer + +0.3.4 (2015-11-07) +------------------ + 0.3.3 (2014-06-15) ------------------ * fixed cmake find for eigen in indigo diff --git a/hector_compressed_map_transport/CMakeLists.txt b/hector_compressed_map_transport/CMakeLists.txt index fa76652f..3d9711f0 100644 --- a/hector_compressed_map_transport/CMakeLists.txt +++ b/hector_compressed_map_transport/CMakeLists.txt @@ -4,13 +4,23 @@ project(hector_compressed_map_transport) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS cmake_modules cv_bridge geometry_msgs hector_map_tools image_transport nav_msgs sensor_msgs) +find_package(catkin REQUIRED COMPONENTS cv_bridge geometry_msgs hector_map_tools image_transport nav_msgs sensor_msgs) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) -find_package(Eigen REQUIRED) -include_directories(${Eigen_INCLUDE_DIRS}) -add_definitions(${Eigen_DEFINITIONS}) + +# Find Eigen3 (from http://wiki.ros.org/jade/Migration) +find_package(Eigen3) +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() find_package(OpenCV REQUIRED) include_directories(${OpenCV_INCLUDE_DIRS}) @@ -57,7 +67,7 @@ catkin_package( # INCLUDE_DIRS include # LIBRARIES hector_compressed_map_transport # CATKIN_DEPENDS cv_bridge geometry_msgs hector_map_tools image_transport nav_msgs opencv2 sensor_msgs -# DEPENDS eigen opencv2 +# DEPENDS EIGEN3 opencv2 ) ########### @@ -69,6 +79,7 @@ catkin_package( # include_directories(include) include_directories( ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) ## Declare a cpp library diff --git a/hector_compressed_map_transport/package.xml b/hector_compressed_map_transport/package.xml index 0c243058..adda2e0d 100644 --- a/hector_compressed_map_transport/package.xml +++ b/hector_compressed_map_transport/package.xml @@ -1,7 +1,7 @@ hector_compressed_map_transport - 0.3.3 + 0.3.5 hector_compressed_map_transport provides means for transporting compressed map data through the use of image_transport. @@ -39,7 +39,6 @@ catkin - cmake_modules cv_bridge geometry_msgs hector_map_tools diff --git a/hector_compressed_map_transport/src/map_to_image_node.cpp b/hector_compressed_map_transport/src/map_to_image_node.cpp index ad01a0e0..1f6fe921 100644 --- a/hector_compressed_map_transport/src/map_to_image_node.cpp +++ b/hector_compressed_map_transport/src/map_to_image_node.cpp @@ -100,7 +100,7 @@ class MapAsImageProvider cv::Mat* map_mat = &cv_img_full_.image; // resize cv image if it doesn't have the same dimensions as the map - if ( (map_mat->rows != size_y) && (map_mat->cols != size_x)){ + if ( (map_mat->rows != size_y) || (map_mat->cols != size_x)){ *map_mat = cv::Mat(size_y, size_x, CV_8U); } @@ -113,7 +113,7 @@ class MapAsImageProvider for (int y = size_y_rev; y >= 0; --y){ - int idx_map_y = size_x * (size_y -y); + int idx_map_y = size_x * (size_y_rev -y); int idx_img_y = size_x * y; for (int x = 0; x < size_x; ++x){ diff --git a/hector_geotiff/CHANGELOG.rst b/hector_geotiff/CHANGELOG.rst index adf0eeaa..1f2d3e00 100644 --- a/hector_geotiff/CHANGELOG.rst +++ b/hector_geotiff/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package hector_geotiff ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ +* Use the FindEigen3.cmake module provided by Eigen +* hector_geotiff/hector_geotiff_plugins: added possibility to specify Color of robot path in the geotiff file in order to allow multiple color robot paths +* Contributors: Dorothea Koert, Johannes Meyer + +0.3.4 (2015-11-07) +------------------ +* Removes trailing spaces and fixes indents +* Contributors: YuK_Ota + 0.3.3 (2014-06-15) ------------------ * fixed cmake find for eigen in indigo diff --git a/hector_geotiff/CMakeLists.txt b/hector_geotiff/CMakeLists.txt index 038ba6ea..331686e6 100644 --- a/hector_geotiff/CMakeLists.txt +++ b/hector_geotiff/CMakeLists.txt @@ -4,16 +4,25 @@ project(hector_geotiff) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS cmake_modules hector_map_tools hector_nav_msgs nav_msgs pluginlib roscpp std_msgs) +find_package(catkin REQUIRED COMPONENTS hector_map_tools hector_nav_msgs nav_msgs pluginlib roscpp std_msgs) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) find_package(Qt4 4.6 COMPONENTS QtCore QtGui REQUIRED) -find_package(Eigen REQUIRED) -include_directories(${Eigen_INCLUDE_DIRS}) -add_definitions(${Eigen_DEFINITIONS}) +# Find Eigen3 (from http://wiki.ros.org/jade/Migration) +find_package(Eigen3) +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() include(${QT_USE_FILE}) @@ -60,7 +69,7 @@ catkin_package( INCLUDE_DIRS include LIBRARIES geotiff_writer CATKIN_DEPENDS hector_map_tools hector_nav_msgs nav_msgs pluginlib roscpp std_msgs - DEPENDS Eigen QT + DEPENDS EIGEN3 QT ) ########### @@ -72,6 +81,7 @@ catkin_package( include_directories(include include/hector_geotiff) include_directories( ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) add_library(geotiff_writer src/geotiff_writer/geotiff_writer.cpp) diff --git a/hector_geotiff/include/hector_geotiff/geotiff_writer.h b/hector_geotiff/include/hector_geotiff/geotiff_writer.h index 3c71ae1c..6aaf4206 100644 --- a/hector_geotiff/include/hector_geotiff/geotiff_writer.h +++ b/hector_geotiff/include/hector_geotiff/geotiff_writer.h @@ -64,7 +64,10 @@ class GeotiffWriter : public MapWriterInterface void drawBackgroundCheckerboard(); void drawMap(const nav_msgs::OccupancyGrid& map, bool draw_explored_space_grid = true); void drawObjectOfInterest(const Eigen::Vector2f& coords, const std::string& txt, const Color& color); - void drawPath(const Eigen::Vector3f& start, const std::vector& points); + inline virtual void drawPath(const Eigen::Vector3f& start, const std::vector& points){ + drawPath(start, points, 120,0,240); + } + void drawPath(const Eigen::Vector3f& start, const std::vector& points, int color_r, int color_g, int color_b); void drawCoords(); std::string getBasePathAndFileName() const; void writeGeotiffImage(); diff --git a/hector_geotiff/include/hector_geotiff/map_writer_interface.h b/hector_geotiff/include/hector_geotiff/map_writer_interface.h index 608b66b9..a2ed1fa2 100644 --- a/hector_geotiff/include/hector_geotiff/map_writer_interface.h +++ b/hector_geotiff/include/hector_geotiff/map_writer_interface.h @@ -43,7 +43,13 @@ class MapWriterInterface{ virtual std::string getBasePathAndFileName() const = 0; virtual void drawObjectOfInterest(const Eigen::Vector2f& coords, const std::string& txt, const Color& color) = 0; - virtual void drawPath(const Eigen::Vector3f& start, const std::vector& points) = 0; + //virtual void drawPath(const Eigen::Vector3f& start, const std::vector& points) = 0; + + inline virtual void drawPath(const Eigen::Vector3f& start, const std::vector& points){ + drawPath(start, points, 120,0,240); + } + virtual void drawPath(const Eigen::Vector3f& start, const std::vector& points, int color_r, int color_g, int color_b) = 0; + }; } diff --git a/hector_geotiff/launch/geotiff_mapper.launch b/hector_geotiff/launch/geotiff_mapper.launch index 366ec19c..ed96888c 100644 --- a/hector_geotiff/launch/geotiff_mapper.launch +++ b/hector_geotiff/launch/geotiff_mapper.launch @@ -1,12 +1,12 @@ - - - - - - + + + + + + diff --git a/hector_geotiff/package.xml b/hector_geotiff/package.xml index 3856a124..8f15a0de 100644 --- a/hector_geotiff/package.xml +++ b/hector_geotiff/package.xml @@ -1,7 +1,7 @@ hector_geotiff - 0.3.3 + 0.3.5 hector_geotiff provides a node that can be used to save occupancy grid map, robot trajectory and object of interest data to RoboCup Rescue compliant GeoTiff images. @@ -38,7 +38,6 @@ catkin - cmake_modules hector_map_tools hector_nav_msgs nav_msgs @@ -46,6 +45,7 @@ roscpp std_msgs libqt4-dev + hector_map_tools hector_nav_msgs nav_msgs diff --git a/hector_geotiff/src/geotiff_writer/geotiff_writer.cpp b/hector_geotiff/src/geotiff_writer/geotiff_writer.cpp index 33c70ce5..b6e0f0bc 100644 --- a/hector_geotiff/src/geotiff_writer/geotiff_writer.cpp +++ b/hector_geotiff/src/geotiff_writer/geotiff_writer.cpp @@ -403,7 +403,7 @@ void GeotiffWriter::drawObjectOfInterest(const Eigen::Vector2f& coords, const st qPainter.drawText(ellipse_shape,Qt::AlignCenter , tmp); } -void GeotiffWriter::drawPath(const Eigen::Vector3f& start, const std::vector& points) +void GeotiffWriter::drawPath(const Eigen::Vector3f& start, const std::vector& points,int color_r, int color_g, int color_b) { QPainter qPainter(&image); @@ -426,7 +426,7 @@ void GeotiffWriter::drawPath(const Eigen::Vector3f& start, const std::vector hector_geotiff_plugins - 0.3.3 + 0.3.5 hector_geotiff_plugins contains plugins that extend geotiff maps generated by hector_geotiff. diff --git a/hector_geotiff_plugins/src/trajectory_geotiff_plugin.cpp b/hector_geotiff_plugins/src/trajectory_geotiff_plugin.cpp index 6de61963..5aaf9603 100644 --- a/hector_geotiff_plugins/src/trajectory_geotiff_plugin.cpp +++ b/hector_geotiff_plugins/src/trajectory_geotiff_plugin.cpp @@ -57,6 +57,9 @@ class TrajectoryMapWriter : public MapWriterPluginInterface std::string name_; bool draw_all_objects_; std::string class_id_; + int path_color_r_; + int path_color_g_; + int path_color_b_; }; TrajectoryMapWriter::TrajectoryMapWriter() @@ -71,7 +74,11 @@ void TrajectoryMapWriter::initialize(const std::string& name) ros::NodeHandle plugin_nh("~/" + name); std::string service_name_; + plugin_nh.param("service_name", service_name_, std::string("trajectory")); + plugin_nh.param("path_color_r", path_color_r_, 120); + plugin_nh.param("path_color_g", path_color_g_, 0); + plugin_nh.param("path_color_b", path_color_b_, 240); service_client_ = nh_.serviceClient(service_name_); @@ -106,7 +113,7 @@ void TrajectoryMapWriter::draw(MapWriterInterface *interface) if (size > 0){ //Eigen::Vector3f startVec(pose_vector[0].x,pose_vector[0].y,pose_vector[0].z); Eigen::Vector3f startVec(pointVec[0].x(),pointVec[0].y(),0.0f); - interface->drawPath(startVec, pointVec); + interface->drawPath(startVec, pointVec, path_color_r_, path_color_g_, path_color_b_); } } diff --git a/hector_imu_attitude_to_tf/CHANGELOG.rst b/hector_imu_attitude_to_tf/CHANGELOG.rst index 01a39572..c314a2dd 100644 --- a/hector_imu_attitude_to_tf/CHANGELOG.rst +++ b/hector_imu_attitude_to_tf/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hector_imu_attitude_to_tf ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ +* hector_imu_attitude_to_tf: fixed default values of the base_frame and base_stabilized_frame parameters (fix #20) +* Contributors: Johannes Meyer + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_imu_attitude_to_tf/package.xml b/hector_imu_attitude_to_tf/package.xml index 2285cbff..22efc389 100644 --- a/hector_imu_attitude_to_tf/package.xml +++ b/hector_imu_attitude_to_tf/package.xml @@ -1,7 +1,7 @@ hector_imu_attitude_to_tf - 0.3.3 + 0.3.5 hector_imu_attitude_to_tf is a lightweight node that can be used to publish the roll/pitch attitude angles reported via a imu message to tf. diff --git a/hector_imu_attitude_to_tf/src/imu_attitude_to_tf_node.cpp b/hector_imu_attitude_to_tf/src/imu_attitude_to_tf_node.cpp index 7a3de4d5..fc4dbcdc 100644 --- a/hector_imu_attitude_to_tf/src/imu_attitude_to_tf_node.cpp +++ b/hector_imu_attitude_to_tf/src/imu_attitude_to_tf_node.cpp @@ -64,8 +64,8 @@ int main(int argc, char **argv) { ros::NodeHandle n; ros::NodeHandle pn("~"); - pn.param("base_stabilized_frame", p_base_stabilized_frame_, std::string("base_stabilized_frame")); - pn.param("base_frame", p_base_frame_, std::string("base_frame")); + pn.param("base_stabilized_frame", p_base_stabilized_frame_, std::string("base_stabilized")); + pn.param("base_frame", p_base_frame_, std::string("base_link")); tfB_ = new tf::TransformBroadcaster(); transform_.getOrigin().setX(0.0); diff --git a/hector_imu_tools/CHANGELOG.rst b/hector_imu_tools/CHANGELOG.rst index 69014fc9..83395c5e 100644 --- a/hector_imu_tools/CHANGELOG.rst +++ b/hector_imu_tools/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package hector_imu_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ +* Fix sim setup +* remap for bertl setup +* Contributors: Florian Kunz, kohlbrecher + 0.3.3 (2014-06-15) ------------------ * hector_imu_tools: Basics of simple height etimation diff --git a/hector_imu_tools/package.xml b/hector_imu_tools/package.xml index d1f3c998..6d6a6e48 100644 --- a/hector_imu_tools/package.xml +++ b/hector_imu_tools/package.xml @@ -1,7 +1,7 @@ hector_imu_tools - 0.3.3 + 0.3.5 hector_imu_tools provides some tools for processing IMU messages diff --git a/hector_map_server/CHANGELOG.rst b/hector_map_server/CHANGELOG.rst index 019a79cb..652cf4b5 100644 --- a/hector_map_server/CHANGELOG.rst +++ b/hector_map_server/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package hector_map_server ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_map_server/package.xml b/hector_map_server/package.xml index b1af7438..400186d7 100644 --- a/hector_map_server/package.xml +++ b/hector_map_server/package.xml @@ -1,7 +1,7 @@ hector_map_server - 0.3.3 + 0.3.5 hector_map_server provides a service for retrieving the map, as well as for raycasting based obstacle queries (finds next obstacle in the map, given start and endpoint in any tf coordinate frame). diff --git a/hector_map_tools/CHANGELOG.rst b/hector_map_tools/CHANGELOG.rst index 6411ec78..c8dc4198 100644 --- a/hector_map_tools/CHANGELOG.rst +++ b/hector_map_tools/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hector_map_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ +* -Fix severe bug when not using square size maps (would results in completely wrong obstacle distances and coordinates) +* Contributors: Stefan Kohlbrecher + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_map_tools/CMakeLists.txt b/hector_map_tools/CMakeLists.txt index d872b253..6d305e94 100644 --- a/hector_map_tools/CMakeLists.txt +++ b/hector_map_tools/CMakeLists.txt @@ -9,6 +9,18 @@ find_package(catkin REQUIRED COMPONENTS nav_msgs) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) +# Find Eigen3 (from http://wiki.ros.org/jade/Migration) +find_package(Eigen3) +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed @@ -52,7 +64,7 @@ catkin_package( INCLUDE_DIRS include # LIBRARIES hector_map_tools CATKIN_DEPENDS nav_msgs - DEPENDS Eigen + DEPENDS EIGEN3 ) ########### @@ -64,6 +76,7 @@ catkin_package( # include_directories(include) include_directories( ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) ## Declare a cpp library diff --git a/hector_map_tools/package.xml b/hector_map_tools/package.xml index 41e7d091..37b373e2 100644 --- a/hector_map_tools/package.xml +++ b/hector_map_tools/package.xml @@ -1,7 +1,7 @@ hector_map_tools - 0.3.3 + 0.3.5 hector_map_tools contains some functions related to accessing information from OccupancyGridMap maps. Currently consists of a single header. diff --git a/hector_mapping/CHANGELOG.rst b/hector_mapping/CHANGELOG.rst index d635aa4b..bc77e697 100644 --- a/hector_mapping/CHANGELOG.rst +++ b/hector_mapping/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hector_mapping ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ +* Use the FindEigen3.cmake module provided by Eigen +* Contributors: Johannes Meyer + +0.3.4 (2015-11-07) +------------------ + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_mapping/CMakeLists.txt b/hector_mapping/CMakeLists.txt index e60d2753..7b5a3c95 100644 --- a/hector_mapping/CMakeLists.txt +++ b/hector_mapping/CMakeLists.txt @@ -4,16 +4,24 @@ project(hector_mapping) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS cmake_modules roscpp nav_msgs visualization_msgs tf message_filters laser_geometry tf_conversions message_generation) +find_package(catkin REQUIRED COMPONENTS roscpp nav_msgs visualization_msgs tf message_filters laser_geometry tf_conversions message_generation) ## System dependencies are found with CMake's conventions find_package(Boost REQUIRED COMPONENTS thread signals) include_directories(${Boost_INCLUDE_DIRS}) -find_package(Eigen REQUIRED) -include_directories(${EIGEN_INCLUDE_DIRS}) -add_definitions(${EIGEN_DEFINITIONS}) - +# Find Eigen3 (from http://wiki.ros.org/jade/Migration) +find_package(Eigen3) +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed @@ -56,7 +64,7 @@ catkin_package( INCLUDE_DIRS include # LIBRARIES hector_mapping CATKIN_DEPENDS roscpp nav_msgs visualization_msgs tf message_filters laser_geometry tf_conversions message_runtime - DEPENDS Eigen + DEPENDS EIGEN3 ) ########### @@ -68,6 +76,7 @@ catkin_package( include_directories(include include/hector_slam_lib) include_directories( ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) ## Declare a cpp library diff --git a/hector_mapping/package.xml b/hector_mapping/package.xml index 22d0575c..564bca75 100644 --- a/hector_mapping/package.xml +++ b/hector_mapping/package.xml @@ -1,7 +1,7 @@ hector_mapping - 0.3.3 + 0.3.5 hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). @@ -41,7 +41,6 @@ catkin - cmake_modules roscpp nav_msgs visualization_msgs diff --git a/hector_mapping/src/HectorMappingRos.cpp b/hector_mapping/src/HectorMappingRos.cpp index 906c2cde..d8cfdcb5 100644 --- a/hector_mapping/src/HectorMappingRos.cpp +++ b/hector_mapping/src/HectorMappingRos.cpp @@ -326,6 +326,7 @@ void HectorMappingRos::scanCallback(const sensor_msgs::LaserScan& scan) tmp.pose = poseInfoContainer_.getPoseWithCovarianceStamped().pose; tmp.header = poseInfoContainer_.getPoseWithCovarianceStamped().header; + tmp.child_frame_id = p_base_frame_; odometryPublisher_.publish(tmp); } diff --git a/hector_marker_drawing/CHANGELOG.rst b/hector_marker_drawing/CHANGELOG.rst index 232994e0..90eda26c 100644 --- a/hector_marker_drawing/CHANGELOG.rst +++ b/hector_marker_drawing/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package hector_marker_drawing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ +* Use the FindEigen3.cmake module provided by Eigen +* Contributors: Johannes Meyer + +0.3.4 (2015-11-07) +------------------ + 0.3.3 (2014-06-15) ------------------ * fixed cmake find for eigen in indigo diff --git a/hector_marker_drawing/CMakeLists.txt b/hector_marker_drawing/CMakeLists.txt index bbf140a5..af7a2ef7 100644 --- a/hector_marker_drawing/CMakeLists.txt +++ b/hector_marker_drawing/CMakeLists.txt @@ -4,14 +4,23 @@ project(hector_marker_drawing) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin REQUIRED COMPONENTS cmake_modules roscpp visualization_msgs) +find_package(catkin REQUIRED COMPONENTS roscpp visualization_msgs) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) -find_package(Eigen REQUIRED) -include_directories(${EIGEN_INCLUDE_DIRS}) -add_definitions(${EIGEN_DEFINITIONS}) +# Find Eigen3 (from http://wiki.ros.org/jade/Migration) +find_package(Eigen3) +if(NOT EIGEN3_FOUND) + # Fallback to cmake_modules + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only + # Possibly map additional variables to the EIGEN3_ prefix. +else() + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed @@ -55,7 +64,7 @@ catkin_package( INCLUDE_DIRS include # LIBRARIES hector_marker_drawing CATKIN_DEPENDS roscpp visualization_msgs - DEPENDS Eigen + DEPENDS EIGEN3 ) ########### @@ -67,6 +76,7 @@ catkin_package( include_directories(include) include_directories( ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} ) ## Declare a cpp library diff --git a/hector_marker_drawing/package.xml b/hector_marker_drawing/package.xml index 90f4ed1b..bc4d9b62 100644 --- a/hector_marker_drawing/package.xml +++ b/hector_marker_drawing/package.xml @@ -1,7 +1,7 @@ hector_marker_drawing - 0.3.3 + 0.3.5 hector_marker_drawing provides convenience functions for easier publishing of visualization markers. @@ -38,7 +38,6 @@ catkin - cmake_modules roscpp visualization_msgs eigen diff --git a/hector_nav_msgs/CHANGELOG.rst b/hector_nav_msgs/CHANGELOG.rst index 3943db81..458aca0e 100644 --- a/hector_nav_msgs/CHANGELOG.rst +++ b/hector_nav_msgs/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package hector_nav_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ +* hector_nav_msgs: removed yaw member from GetNormal response + yaw is implicitly given by the normal vector +* Contributors: Dorothea Koert + 0.3.3 (2014-06-15) ------------------ * added GetNormal service, that returns normal and orientation of an occupied cell diff --git a/hector_nav_msgs/package.xml b/hector_nav_msgs/package.xml index 9c210729..fe0699a4 100644 --- a/hector_nav_msgs/package.xml +++ b/hector_nav_msgs/package.xml @@ -1,7 +1,7 @@ hector_nav_msgs - 0.3.3 + 0.3.5 hector_nav_msgs contains messages and services used in the hector_slam stack. diff --git a/hector_slam/CHANGELOG.rst b/hector_slam/CHANGELOG.rst index efca5416..21f1da41 100644 --- a/hector_slam/CHANGELOG.rst +++ b/hector_slam/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package hector_slam ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_slam/package.xml b/hector_slam/package.xml index 4aebec70..62adafa8 100644 --- a/hector_slam/package.xml +++ b/hector_slam/package.xml @@ -1,7 +1,7 @@ hector_slam - 0.3.3 + 0.3.5 The hector_slam metapackage that installs hector_mapping and related packages. diff --git a/hector_slam_launch/CHANGELOG.rst b/hector_slam_launch/CHANGELOG.rst index 056ffa8c..dfb4eda9 100644 --- a/hector_slam_launch/CHANGELOG.rst +++ b/hector_slam_launch/CHANGELOG.rst @@ -2,6 +2,15 @@ Changelog for package hector_slam_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.3.5 (2016-06-24) +------------------ + +0.3.4 (2015-11-07) +------------------ +* Removes trailing spaces and fixes indents +* "rviz_cfg" directory in the repository version. +* Contributors: YuK_Ota, dani-carbonell + 0.3.3 (2014-06-15) ------------------ diff --git a/hector_slam_launch/launch/cityflyer_logfile_processing.launch b/hector_slam_launch/launch/cityflyer_logfile_processing.launch index 35d9af61..744a4e83 100644 --- a/hector_slam_launch/launch/cityflyer_logfile_processing.launch +++ b/hector_slam_launch/launch/cityflyer_logfile_processing.launch @@ -4,38 +4,38 @@ - - + - - + + - + - + - + - + - + - + - + - + - + - + @@ -26,7 +26,7 @@ - + diff --git a/hector_slam_launch/launch/postproc_data.launch b/hector_slam_launch/launch/postproc_data.launch index dfbb4535..e948447a 100644 --- a/hector_slam_launch/launch/postproc_data.launch +++ b/hector_slam_launch/launch/postproc_data.launch @@ -4,7 +4,7 @@ - @@ -13,9 +13,9 @@ - + - + diff --git a/hector_slam_launch/launch/pr2os.launch b/hector_slam_launch/launch/pr2os.launch index a5a1b312..231537e3 100644 --- a/hector_slam_launch/launch/pr2os.launch +++ b/hector_slam_launch/launch/pr2os.launch @@ -3,34 +3,34 @@ - + - - + + - + - + - + - + - +