diff --git a/perception/mil_vision/CMakeLists.txt b/perception/mil_vision/CMakeLists.txt index dda345ad..3e2c246b 100644 --- a/perception/mil_vision/CMakeLists.txt +++ b/perception/mil_vision/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(catkin pcl_ros tf2_sensor_msgs tf2_geometry_msgs + mil_tools ) find_package(PCL 1.7 REQUIRED) @@ -83,7 +84,7 @@ add_library( src/mil_vision_lib/colorizer/color_observation.cpp ) target_include_directories(mil_vision_lib PUBLIC include/mil_vision_lib) -target_link_libraries(mil_vision_lib mil_tools_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${PCL_COMMON_LIBRARIES} ${PCL_COMMON_LIBRARIES}) +target_link_libraries(mil_vision_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${PCL_COMMON_LIBRARIES} ${PCL_COMMON_LIBRARIES}) add_executable(camera_stream_demo nodes/camera_stream_demo.cpp) add_dependencies(camera_stream_demo mil_vision_lib ${catkin_EXPORTED_TARGETS}) diff --git a/perception/mil_vision/include/mil_vision_lib/active_contours.hpp b/perception/mil_vision/include/mil_vision_lib/active_contours.hpp index f3a4d658..ed187f0e 100644 --- a/perception/mil_vision/include/mil_vision_lib/active_contours.hpp +++ b/perception/mil_vision/include/mil_vision_lib/active_contours.hpp @@ -14,7 +14,7 @@ #include #include -namespace nav +namespace mil_vision { class SegmentDescription; @@ -65,4 +65,4 @@ class ActiveContour ActiveContour(); }; -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/colorizer/camera_observer.hpp b/perception/mil_vision/include/mil_vision_lib/colorizer/camera_observer.hpp index 73950829..58eefcc3 100644 --- a/perception/mil_vision/include/mil_vision_lib/colorizer/camera_observer.hpp +++ b/perception/mil_vision/include/mil_vision_lib/colorizer/camera_observer.hpp @@ -6,7 +6,7 @@ #include #include -namespace nav{ +namespace mil_vision{ class CameraObserver { @@ -42,4 +42,4 @@ class CameraObserver }; -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/colorizer/color_observation.hpp b/perception/mil_vision/include/mil_vision_lib/colorizer/color_observation.hpp index 890f8dff..fb7ec651 100644 --- a/perception/mil_vision/include/mil_vision_lib/colorizer/color_observation.hpp +++ b/perception/mil_vision/include/mil_vision_lib/colorizer/color_observation.hpp @@ -6,7 +6,7 @@ #include -namespace nav{ +namespace mil_vision{ struct alignas(16) ColorObservation { @@ -42,4 +42,4 @@ struct PointColorStats int n; }; -} //namespace nav \ No newline at end of file +} //namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/include/mil_vision_lib/colorizer/common.hpp b/perception/mil_vision/include/mil_vision_lib/colorizer/common.hpp index 465e6240..2930fd3f 100644 --- a/perception/mil_vision/include/mil_vision_lib/colorizer/common.hpp +++ b/perception/mil_vision/include/mil_vision_lib/colorizer/common.hpp @@ -20,11 +20,11 @@ #include #include -namespace nav{ +namespace mil_vision{ template using PCD = pcl::PointCloud; template using PCDPtr = std::shared_ptr>; template using SPtrVector = std::vector>; template using UPtrVector = std::vector>; -} // namespace nav \ No newline at end of file +} // namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/include/mil_vision_lib/colorizer/pcd_colorizer.hpp b/perception/mil_vision/include/mil_vision_lib/colorizer/pcd_colorizer.hpp index a81b1747..03a81e67 100644 --- a/perception/mil_vision/include/mil_vision_lib/colorizer/pcd_colorizer.hpp +++ b/perception/mil_vision/include/mil_vision_lib/colorizer/pcd_colorizer.hpp @@ -8,7 +8,7 @@ #include #include -namespace nav{ +namespace mil_vision{ class PcdColorizer{ /* @@ -69,4 +69,4 @@ class PcdColorizer{ }; // end class PcdColorizer -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/colorizer/single_cloud_processor.hpp b/perception/mil_vision/include/mil_vision_lib/colorizer/single_cloud_processor.hpp index 675c0a5c..446b9b78 100644 --- a/perception/mil_vision/include/mil_vision_lib/colorizer/single_cloud_processor.hpp +++ b/perception/mil_vision/include/mil_vision_lib/colorizer/single_cloud_processor.hpp @@ -7,7 +7,7 @@ #include #include -namespace nav { +namespace mil_vision { class SingleCloudProcessor { @@ -38,4 +38,4 @@ class SingleCloudProcessor }; -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/cv_tools.hpp b/perception/mil_vision/include/mil_vision_lib/cv_tools.hpp index 3a9fba30..bd608942 100644 --- a/perception/mil_vision/include/mil_vision_lib/cv_tools.hpp +++ b/perception/mil_vision/include/mil_vision_lib/cv_tools.hpp @@ -23,7 +23,7 @@ // #define SEGMENTATION_DEBUG -namespace nav { +namespace mil_vision { /// UTILS diff --git a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame.hpp b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame.hpp index dee3c788..c3cf6c5a 100644 --- a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame.hpp +++ b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame.hpp @@ -11,7 +11,7 @@ #include -namespace nav +namespace mil_vision { enum class PixelType @@ -139,7 +139,7 @@ class CameraFrame float_t _img_scale = 1.0f; // Stores the pixel data type - nav::PixelType TYPE = nav::PixelType::_UNKNOWN; + mil_vision::PixelType TYPE = mil_vision::PixelType::_UNKNOWN; /////////////////////////////////////////////////////////////////////////////////////////////// @@ -198,5 +198,5 @@ catch(const std::exception &e) ROS_WARN(e.what()); } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame_sequence.hpp b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame_sequence.hpp index 7b34d7ee..3369f122 100644 --- a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame_sequence.hpp +++ b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_frame_sequence.hpp @@ -6,7 +6,7 @@ #include #include -namespace nav +namespace mil_vision { template @@ -68,4 +68,4 @@ class CameraFrameSequence }; -} // namespace nav \ No newline at end of file +} // namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_model.hpp b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_model.hpp index 477b5497..3e6c7ee2 100644 --- a/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_model.hpp +++ b/perception/mil_vision/include/mil_vision_lib/image_acquisition/camera_model.hpp @@ -3,7 +3,7 @@ #include #include -namespace nav{ +namespace mil_vision{ template class CameraModel{ @@ -59,4 +59,4 @@ Eigen::Matrix CameraModel::get_projection_matrix() return K * R * aug; } -} // namespace nav \ No newline at end of file +} // namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/include/mil_vision_lib/image_acquisition/ros_camera_stream.hpp b/perception/mil_vision/include/mil_vision_lib/image_acquisition/ros_camera_stream.hpp index d68f23e3..bfe1a120 100644 --- a/perception/mil_vision/include/mil_vision_lib/image_acquisition/ros_camera_stream.hpp +++ b/perception/mil_vision/include/mil_vision_lib/image_acquisition/ros_camera_stream.hpp @@ -18,7 +18,7 @@ #include -namespace nav +namespace mil_vision { template @@ -130,7 +130,7 @@ class ROSCameraStream : public CameraFrameSequence bool ROSCameraStream::init(std::string &camera_topic) { - using mil::tools::operator "" _s; // convert raw string literal to std::string + using mil_tools::operator "" _s; // convert raw string literal to std::string _img_topic = camera_topic; bool success = false; image_transport::CameraSubscriber cam_sub; @@ -237,7 +237,7 @@ template typename ROSCameraStream::CamFrameConstPtr ROSCameraStream::getFrameFromTime(ros::Time desired_time) { - using mil::tools::operator "" _s; + using mil_tools::operator "" _s; // Check bounds on time if(desired_time < this->_start_time || desired_time > this->_end_time) @@ -269,7 +269,7 @@ template typename ROSCameraStream::CamFrameConstPtr ROSCameraStream::operator[](int i) { - using mil::tools::operator "" _s; + using mil_tools::operator "" _s; // Prevent adding new frames while frames are being accessed _mtx.lock(); @@ -337,4 +337,4 @@ ROSCameraStream::~ROSCameraStream() _cb_queue.disable(); } -} // namespace nav \ No newline at end of file +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/image_filtering.hpp b/perception/mil_vision/include/mil_vision_lib/image_filtering.hpp index 7200f102..3b7b08cf 100644 --- a/perception/mil_vision/include/mil_vision_lib/image_filtering.hpp +++ b/perception/mil_vision/include/mil_vision_lib/image_filtering.hpp @@ -7,7 +7,7 @@ #include -namespace nav +namespace mil_vision { /* @@ -39,4 +39,4 @@ cv::Mat makeRotInvariant(const cv::Mat &kernel, int rotations=8); */ float getRadialSymmetryAngle(const cv::Mat &kernel, float ang_res=0.1, bool deg=false); -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/include/mil_vision_lib/pcd_sub_pub_algorithm.hpp b/perception/mil_vision/include/mil_vision_lib/pcd_sub_pub_algorithm.hpp index 42f3b700..7ef4bd3e 100644 --- a/perception/mil_vision/include/mil_vision_lib/pcd_sub_pub_algorithm.hpp +++ b/perception/mil_vision/include/mil_vision_lib/pcd_sub_pub_algorithm.hpp @@ -7,7 +7,7 @@ #include -namespace nav{ +namespace mil_vision{ template class PcdSubPubAlgorithm{ @@ -78,4 +78,4 @@ class PcdSubPubAlgorithm{ std::string _err_msg; }; -} //namespace nav \ No newline at end of file +} //namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/include/mil_vision_lib/point_cloud_algorithms.hpp b/perception/mil_vision/include/mil_vision_lib/point_cloud_algorithms.hpp index 12558c2b..295dddcf 100644 --- a/perception/mil_vision/include/mil_vision_lib/point_cloud_algorithms.hpp +++ b/perception/mil_vision/include/mil_vision_lib/point_cloud_algorithms.hpp @@ -8,7 +8,7 @@ #include #include -namespace nav{ +namespace mil_vision { class PcdSubPubAlgorithm{ /* @@ -67,4 +67,4 @@ class PcdColorizer : public PcdSubPubAlgorithm{ sensor_msgs::CameraInfoConstPtr latest_frame_info_msg; }; -} // namwspace nav \ No newline at end of file +} // namwspace nav diff --git a/perception/mil_vision/include/mil_vision_lib/visualization.hpp b/perception/mil_vision/include/mil_vision_lib/visualization.hpp index d3c420c0..00b92f56 100644 --- a/perception/mil_vision/include/mil_vision_lib/visualization.hpp +++ b/perception/mil_vision/include/mil_vision_lib/visualization.hpp @@ -8,7 +8,7 @@ #include "ros/ros.h" #include "geometry_msgs/Pose.h" -namespace nav { +namespace mil_vision { // ******* 3D Visualization ******* class RvizVisualizer { diff --git a/perception/mil_vision/nodes/camera_stream_demo.cpp b/perception/mil_vision/nodes/camera_stream_demo.cpp index b6d6fae1..adbab43a 100755 --- a/perception/mil_vision/nodes/camera_stream_demo.cpp +++ b/perception/mil_vision/nodes/camera_stream_demo.cpp @@ -15,7 +15,7 @@ int main(int argc, char **argv) // Template argument should be cv::Vec3b for color images or uint8_t // For grayscale images - nav::ROSCameraStream left_cam_stream(nh, history_length); // Constructs empty inactive + mil_vision::ROSCameraStream left_cam_stream(nh, history_length); // Constructs empty inactive // camera stream object if(!left_cam_stream.init(cam_topic)) // Initializes object, if sucessful, object will automatically return -1; // store a history of images published to cam_topic in its buffer diff --git a/perception/mil_vision/src/mil_vision_lib/active_contours.cpp b/perception/mil_vision/src/mil_vision_lib/active_contours.cpp index e12ad7ed..a5fb1006 100644 --- a/perception/mil_vision/src/mil_vision_lib/active_contours.cpp +++ b/perception/mil_vision/src/mil_vision_lib/active_contours.cpp @@ -3,7 +3,7 @@ using namespace std; using namespace cv; -namespace nav +namespace mil_vision { namespace Perturbations @@ -226,7 +226,7 @@ bool ClosedCurve::validateCurve(std::vector& curve) if(count > 1) { auto conflict_pt = find_if(forbidden_neighbors.begin(), forbidden_neighbors.end(), - [pt](Point2i test_pt){ return nav::Perturbations::isNeighborPoint(pt, test_pt); }); + [pt](Point2i test_pt){ return mil_vision::Perturbations::isNeighborPoint(pt, test_pt); }); cout << "failure pts: " << curve[1] << "\t" << (conflict_pt != forbidden_neighbors.end()? Point2i(0,0) : *conflict_pt) << endl; return false; } @@ -236,7 +236,7 @@ bool ClosedCurve::validateCurve(std::vector& curve) if(count > 0) { auto conflict_pt = find_if(forbidden_neighbors.begin(), forbidden_neighbors.end(), - [pt](Point2i test_pt){ return nav::Perturbations::isNeighborPoint(pt, test_pt); }); + [pt](Point2i test_pt){ return mil_vision::Perturbations::isNeighborPoint(pt, test_pt); }); cout << "failure pts: " << curve[1] << "\t" << (conflict_pt != forbidden_neighbors.end()? Point2i(0,0) : *conflict_pt) << endl; return false; } @@ -250,4 +250,4 @@ vector calcCosts(const Mat& img, vector candid } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/colorizer/camera_observer.cpp b/perception/mil_vision/src/mil_vision_lib/colorizer/camera_observer.cpp index eac494fe..99b83fdd 100644 --- a/perception/mil_vision/src/mil_vision_lib/colorizer/camera_observer.cpp +++ b/perception/mil_vision/src/mil_vision_lib/colorizer/camera_observer.cpp @@ -1,8 +1,8 @@ #include -namespace nav{ +namespace mil_vision{ -using mil::tools::operator "" _s; // converts to std::string +using mil_tools::operator "" _s; // converts to std::string CameraObserver::CameraObserver(ros::NodeHandle &nh, std::string &pcd_in_topic, std::string &cam_topic, size_t hist_size) : _nh{nh}, _cam_stream{nh, hist_size} @@ -70,4 +70,4 @@ ColorObservation::VecImg CameraObserver::get_color_observations(const PCD -namespace nav{ +namespace mil_vision{ UnoccludedPointsImg::UnoccludedPointsImg() // : frame_ptr(frame_ptr), @@ -12,4 +12,4 @@ UnoccludedPointsImg::UnoccludedPointsImg() } -} // namespace nav \ No newline at end of file +} // namespace mil_vision \ No newline at end of file diff --git a/perception/mil_vision/src/mil_vision_lib/colorizer/pcd_colorizer.cpp b/perception/mil_vision/src/mil_vision_lib/colorizer/pcd_colorizer.cpp index 8e3f67a4..210843e6 100644 --- a/perception/mil_vision/src/mil_vision_lib/colorizer/pcd_colorizer.cpp +++ b/perception/mil_vision/src/mil_vision_lib/colorizer/pcd_colorizer.cpp @@ -3,13 +3,13 @@ using namespace std; using namespace cv; -namespace nav{ +namespace mil_vision{ PcdColorizer::PcdColorizer(ros::NodeHandle nh, string input_pcd_topic) : _nh(nh), _img_hist_size{10}, _cloud_processor{nh, input_pcd_topic, _img_hist_size}, _input_pcd_topic{input_pcd_topic}, _output_pcd_topic{input_pcd_topic + "_colored"} { - using mil::tools::operator "" _s; // converts to std::string + using mil_tools::operator "" _s; // converts to std::string try { @@ -52,7 +52,7 @@ void PcdColorizer::_cloud_cb(const PCD<>::ConstPtr &cloud_in) // { // cout << "img hist size: " << _img_hist_size << endl; // // Subscribe to all rectified color img topics -// auto rect_color_topics = mil::tools::getRectifiedImageTopics(true); +// auto rect_color_topics = mil_tools::getRectifiedImageTopics(true); // if(rect_color_topics.size() == 0) // { // _err_msg += "COLORIZER: There are no rectified color camera topics currently publishing on this ROS master ("; @@ -170,4 +170,4 @@ void PcdColorizer::_cloud_cb(const PCD<>::ConstPtr &cloud_in) // } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/colorizer/single_cloud_processor.cpp b/perception/mil_vision/src/mil_vision_lib/colorizer/single_cloud_processor.cpp index cd24af4e..4fdc8bf0 100644 --- a/perception/mil_vision/src/mil_vision_lib/colorizer/single_cloud_processor.cpp +++ b/perception/mil_vision/src/mil_vision_lib/colorizer/single_cloud_processor.cpp @@ -2,15 +2,15 @@ // using namespace std; -namespace nav { +namespace mil_vision { -using mil::tools::operator "" _s; // converts to std::string +using mil_tools::operator "" _s; // converts to std::string SingleCloudProcessor::SingleCloudProcessor(ros::NodeHandle nh, std::string& in_pcd_topic, size_t hist_size) : _nh{nh}, _hist_size{hist_size} { ROS_INFO(("SingleCloudProcessor: Initializing with " + in_pcd_topic).c_str()); - auto rect_color_topics = mil::tools::getRectifiedImageTopics(true); + auto rect_color_topics = mil_tools::getRectifiedImageTopics(true); if(rect_color_topics.size() == 0) { _err_msg += "COLORIZER: There are no rectified color camera topics currently publishing on this ROS master ("; @@ -55,4 +55,4 @@ void SingleCloudProcessor::operator()(const PCD::ConstPtr &pcd) // Summarize Confidence in each point color observation } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/cv_utils.cc b/perception/mil_vision/src/mil_vision_lib/cv_utils.cc index a7f6de7d..07364acd 100644 --- a/perception/mil_vision/src/mil_vision_lib/cv_utils.cc +++ b/perception/mil_vision/src/mil_vision_lib/cv_utils.cc @@ -1,6 +1,6 @@ #include -namespace nav { +namespace mil_vision { cv::Point contour_centroid(Contour &contour) { cv::Moments m = cv::moments(contour, true); @@ -208,7 +208,7 @@ void statistical_image_segmentation(const cv::Mat &src, cv::Mat &dest, // Smooth histogram const int kernel_size = 11; - hist_smooth = nav::smooth_histogram(hist, kernel_size, sigma); + hist_smooth = mil_vision::smooth_histogram(hist, kernel_size, sigma); // Calculate histogram derivative (central finite difference) hist_derivative = hist_smooth.clone(); @@ -218,12 +218,12 @@ void statistical_image_segmentation(const cv::Mat &src, cv::Mat &dest, hist_derivative.at(i) = (hist_smooth.at(i + 1) - hist_smooth.at(i - 1)) / 2.0; } - hist_derivative = nav::smooth_histogram(hist_derivative, kernel_size, sigma); + hist_derivative = mil_vision::smooth_histogram(hist_derivative, kernel_size, sigma); // Find target mode std::vector histogram_modes = - nav::find_local_maxima(hist_smooth, 0.1); - int target_mode = nav::select_hist_mode(histogram_modes, target); + mil_vision::find_local_maxima(hist_smooth, 0.1); + int target_mode = mil_vision::select_hist_mode(histogram_modes, target); ros_log << "Target: " << target << std::endl; ros_log << "Mode Selected: " << target_mode << std::endl; @@ -238,9 +238,9 @@ void statistical_image_segmentation(const cv::Mat &src, cv::Mat &dest, int low_abs_derivative_thresh = std::abs(hist_deriv_stddev[0] * low_thresh_gain); std::vector derivative_maxima = - nav::find_local_maxima(hist_derivative, 0.01); + mil_vision::find_local_maxima(hist_derivative, 0.01); std::vector derivative_minima = - nav::find_local_minima(hist_derivative, 0.01); + mil_vision::find_local_minima(hist_derivative, 0.01); int high_thresh_search_start = target_mode; int low_thresh_search_start = target_mode; ros_log << "high_thresh_search_start: " << target_mode << std::endl; @@ -653,4 +653,4 @@ FrameHistory::get_frame_history(unsigned int frames_requested) { return frame_history; } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/image_filtering.cpp b/perception/mil_vision/src/mil_vision_lib/image_filtering.cpp index 13c52ef4..a7bf1b1b 100644 --- a/perception/mil_vision/src/mil_vision_lib/image_filtering.cpp +++ b/perception/mil_vision/src/mil_vision_lib/image_filtering.cpp @@ -1,11 +1,11 @@ #include -namespace nav +namespace mil_vision { cv::Mat rotateKernel(const cv::Mat &kernel, float theta, bool deg, bool no_expand) { - theta = deg? theta : theta * mil::PI / 180.0f; + theta = deg? theta : theta * mil_tools::PI / 180.0f; cv::Point2f c_org{kernel.cols * 0.5f, kernel.rows * 0.5f}; // center of original if(no_expand) // rotates without expanding the canvas @@ -73,12 +73,12 @@ float getRadialSymmetryAngle(const cv::Mat &kernel, float ang_res, bool deg) cv::Mat elem_wise_mult{original.size(), CV_32S}; cv::multiply(original, original, elem_wise_mult); auto standard = cv::sum(elem_wise_mult)[0]; - float max = deg? 360.0f : 2 * mil::PI; + float max = deg? 360.0f : 2 * mil_tools::PI; float result = max; float best_score = 0; bool left_starting_region = false; - for(float theta = 0.0f; theta < max; theta += (deg? ang_res * 180.0f / mil::PI : ang_res)) + for(float theta = 0.0f; theta < max; theta += (deg? ang_res * 180.0f / mil_tools::PI : ang_res)) { cv::multiply(original, rotateKernel(original, theta, deg, true), elem_wise_mult); double score = standard / cv::sum(elem_wise_mult)[0]; @@ -109,4 +109,4 @@ float getRadialSymmetryAngle(const cv::Mat &kernel, float ang_res, bool deg) return result; } -} // namespace nav +} // namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/point_cloud_algorithms.cc b/perception/mil_vision/src/mil_vision_lib/point_cloud_algorithms.cc index 88d7b854..a0d23231 100644 --- a/perception/mil_vision/src/mil_vision_lib/point_cloud_algorithms.cc +++ b/perception/mil_vision/src/mil_vision_lib/point_cloud_algorithms.cc @@ -3,7 +3,7 @@ using namespace std; using namespace cv; -namespace nav{ +namespace mil_vision { Mat g_color_sequence; @@ -139,4 +139,4 @@ void PcdColorizer::_color_pcd(){ } } -} //namespace nav \ No newline at end of file +} //namespace mil_vision diff --git a/perception/mil_vision/src/mil_vision_lib/visualization.cc b/perception/mil_vision/src/mil_vision_lib/visualization.cc index f3f8293e..6f4ed049 100644 --- a/perception/mil_vision/src/mil_vision_lib/visualization.cc +++ b/perception/mil_vision/src/mil_vision_lib/visualization.cc @@ -1,7 +1,7 @@ #include #include -namespace nav { +namespace mil_vision { RvizVisualizer::RvizVisualizer(std::string rviz_topic) { rviz_pub = nh.advertise(rviz_topic, 1); diff --git a/utils/mil_msgs/CMakeLists.txt b/utils/mil_msgs/CMakeLists.txt index a65ab09c..dac2cdae 100644 --- a/utils/mil_msgs/CMakeLists.txt +++ b/utils/mil_msgs/CMakeLists.txt @@ -5,14 +5,11 @@ find_package(catkin message_generation message_runtime geometry_msgs - tf actionlib interactive_markers std_msgs actionlib_msgs - cmake_modules ) -catkin_python_setup() add_action_files(FILES MoveTo.action @@ -27,17 +24,10 @@ add_message_files(FILES Acceleration.msg ) -find_package(Eigen 3 REQUIRED) -include_directories(${Eigen_INCLUDE_DIRS}) generate_messages( - DEPENDENCIES std_msgs actionlib_msgs geometry_msgs mil_msgs + DEPENDENCIES std_msgs actionlib_msgs geometry_msgs ) catkin_package( - DEPENDS Eigen - CATKIN_DEPENDS message_generation message_runtime geometry_msgs tf actionlib interactive_markers std_msgs actionlib_msgs - INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS} include - LIBRARIES + CATKIN_DEPENDS message_generation message_runtime geometry_msgs actionlib std_msgs actionlib_msgs ) -include_directories(${EIGEN_INCLUDE_DIRS} include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS}) -#install(PROGRAMS scripts/interactive_marker_moveto scripts/velocitymeasurements_to_vector3 scripts/param_saver DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/utils/mil_msgs/mil_msgs/__init__.py b/utils/mil_msgs/mil_msgs/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/utils/mil_msgs/package.xml b/utils/mil_msgs/package.xml index f0cb7cb1..96494287 100644 --- a/utils/mil_msgs/package.xml +++ b/utils/mil_msgs/package.xml @@ -13,21 +13,16 @@ message_runtime actionlib - interactive_markers std_msgs message_generation geometry_msgs - tf actionlib_msgs - cmake_modules message_runtime actionlib - interactive_markers std_msgs message_generation geometry_msgs - tf actionlib_msgs diff --git a/utils/mil_msgs/setup.py b/utils/mil_msgs/setup.py deleted file mode 100644 index aa9637cd..00000000 --- a/utils/mil_msgs/setup.py +++ /dev/null @@ -1,10 +0,0 @@ -# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -setup_args = generate_distutils_setup( - packages=['mil_msgs'], -) - -setup(**setup_args) diff --git a/utils/mil_tools/CMakeLists.txt b/utils/mil_tools/CMakeLists.txt index 4c1e7b9f..0b304579 100644 --- a/utils/mil_tools/CMakeLists.txt +++ b/utils/mil_tools/CMakeLists.txt @@ -8,13 +8,17 @@ find_package(catkin REQUIRED COMPONENTS rospy roscpp cv_bridge + cmake_modules ) +find_package(Eigen 3 REQUIRED) + catkin_package( + DEPENDS Eigen INCLUDE_DIRS include LIBRARIES - mil_tools_lib + mil_tools CATKIN_DEPENDS roscpp cv_bridge @@ -32,11 +36,15 @@ include_directories( SYSTEM ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} + ${Eigen_INCLUDE_DIRS} ) -add_library(mil_tools_lib +add_library(mil_tools src/mil_tools/mil_tools.cpp ) -target_include_directories(mil_tools_lib PUBLIC include) -target_link_libraries(mil_tools_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_include_directories(mil_tools PUBLIC include) +target_link_libraries(mil_tools ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + +install(DIRECTORY include/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) diff --git a/utils/mil_tools/include/mil_tools/mil_tools.hpp b/utils/mil_tools/include/mil_tools/mil_tools.hpp index 90b174e1..30a7b63e 100644 --- a/utils/mil_tools/include/mil_tools/mil_tools.hpp +++ b/utils/mil_tools/include/mil_tools/mil_tools.hpp @@ -7,12 +7,10 @@ #include #include -namespace mil{ +namespace mil_tools{ static const double PI = 3.1415926535897932; -namespace tools -{ // Returns a vector of topic names (std::string) that end with "image_rect_color" // if color is false then it looks for those that end in "image_rect" @@ -28,6 +26,4 @@ inline std::string operator "" _s(const char* str, size_t /*length*/) // Sorts contours by curve length void sortContours(std::vector>& contour_vec, bool ascending=true); -} // namespace mil::tools -} // namespace mil - +} diff --git a/utils/mil_msgs/include/mil_msgs/msg_helpers.h b/utils/mil_tools/include/mil_tools/msg_helpers.h similarity index 98% rename from utils/mil_msgs/include/mil_msgs/msg_helpers.h rename to utils/mil_tools/include/mil_tools/msg_helpers.h index 578467b8..fddbfbfe 100644 --- a/utils/mil_msgs/include/mil_msgs/msg_helpers.h +++ b/utils/mil_tools/include/mil_tools/msg_helpers.h @@ -3,7 +3,7 @@ #include #include -namespace uf_common { +namespace mil_tools { template inline T make_rgba(double r, double g, double b, double a) { diff --git a/utils/mil_msgs/include/mil_msgs/param_helpers.h b/utils/mil_tools/include/mil_tools/param_helpers.h similarity index 99% rename from utils/mil_msgs/include/mil_msgs/param_helpers.h rename to utils/mil_tools/include/mil_tools/param_helpers.h index 09c353b5..4e2881a1 100644 --- a/utils/mil_msgs/include/mil_msgs/param_helpers.h +++ b/utils/mil_tools/include/mil_tools/param_helpers.h @@ -6,7 +6,7 @@ #include "msg_helpers.h" -namespace uf_common { +namespace mil_tools { void fail(std::string const &error_string) { throw std::runtime_error(error_string); } template diff --git a/utils/mil_tools/package.xml b/utils/mil_tools/package.xml index 260b7ddc..03116810 100644 --- a/utils/mil_tools/package.xml +++ b/utils/mil_tools/package.xml @@ -14,6 +14,8 @@ rospy cv_bridge cv_bridge + cmake_modules + diff --git a/utils/mil_msgs/scripts/param_saver b/utils/mil_tools/scripts/param_sever similarity index 95% rename from utils/mil_msgs/scripts/param_saver rename to utils/mil_tools/scripts/param_sever index 95c114fa..4cddcace 100755 --- a/utils/mil_msgs/scripts/param_saver +++ b/utils/mil_tools/scripts/param_sever @@ -4,8 +4,6 @@ import os import random import yaml -import roslib -roslib.load_manifest('uf_common') import rospy diff --git a/utils/mil_tools/src/mil_tools/mil_tools.cpp b/utils/mil_tools/src/mil_tools/mil_tools.cpp index 00fd1c9f..27bb316a 100644 --- a/utils/mil_tools/src/mil_tools/mil_tools.cpp +++ b/utils/mil_tools/src/mil_tools/mil_tools.cpp @@ -1,7 +1,8 @@ #include +#include +#include -namespace mil{ -namespace tools{ +namespace mil_tools { using namespace std; @@ -52,6 +53,4 @@ void sortContours(vector>& contour_vec, bool ascending) } -} // namespace mil::tools -} // namespace mil - +}