Skip to content

Commit

Permalink
REPO: various changes for sub8 integration
Browse files Browse the repository at this point in the history
* fix up namespaces in mil_vision

* move mil_msgs stuff that isnt messages to mil_tools
  • Loading branch information
kev-the-dev committed Apr 10, 2017
1 parent 68a8b50 commit 9ab1f95
Show file tree
Hide file tree
Showing 37 changed files with 93 additions and 114 deletions.
3 changes: 2 additions & 1 deletion perception/mil_vision/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ find_package(catkin
pcl_ros
tf2_sensor_msgs
tf2_geometry_msgs
mil_tools
)

find_package(PCL 1.7 REQUIRED)
Expand Down Expand Up @@ -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})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

namespace nav
namespace mil_vision
{

class SegmentDescription;
Expand Down Expand Up @@ -65,4 +65,4 @@ class ActiveContour
ActiveContour();
};

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <image_geometry/pinhole_camera_model.h>
#include <opencv2/core/eigen.hpp>

namespace nav{
namespace mil_vision{

class CameraObserver
{
Expand Down Expand Up @@ -42,4 +42,4 @@ class CameraObserver

};

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <Eigen/Core>


namespace nav{
namespace mil_vision{

struct alignas(16) ColorObservation
{
Expand Down Expand Up @@ -42,4 +42,4 @@ struct PointColorStats
int n;
};

} //namespace nav
} //namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@
#include <future>
#include <list>

namespace nav{
namespace mil_vision{

template<typename T = pcl::PointXYZ> using PCD = pcl::PointCloud<T>;
template<typename T = pcl::PointXYZ> using PCDPtr = std::shared_ptr<PCD<T>>;
template<typename T> using SPtrVector = std::vector<std::shared_ptr<T>>;
template<typename T> using UPtrVector = std::vector<std::unique_ptr<T>>;

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include <pcl_ros/transforms.h>
#include <tf/transform_listener.h>

namespace nav{
namespace mil_vision{

class PcdColorizer{
/*
Expand Down Expand Up @@ -69,4 +69,4 @@ class PcdColorizer{

}; // end class PcdColorizer

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <pcl_ros/transforms.h>
#include <tf/transform_listener.h>

namespace nav {
namespace mil_vision {

class SingleCloudProcessor
{
Expand Down Expand Up @@ -38,4 +38,4 @@ class SingleCloudProcessor

};

} // namespace nav
} // namespace mil_vision
2 changes: 1 addition & 1 deletion perception/mil_vision/include/mil_vision_lib/cv_tools.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

// #define SEGMENTATION_DEBUG

namespace nav {
namespace mil_vision {

/// UTILS

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <exception>


namespace nav
namespace mil_vision
{

enum class PixelType
Expand Down Expand Up @@ -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;


///////////////////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -198,5 +198,5 @@ catch(const std::exception &e)
ROS_WARN(e.what());
}

} // namespace nav
} // namespace mil_vision

Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <vector>
#include <memory>

namespace nav
namespace mil_vision
{

template<typename cam_model_ptr_t, typename img_scalar_t, typename time_t_,typename float_t = float>
Expand Down Expand Up @@ -68,4 +68,4 @@ class CameraFrameSequence

};

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <Eigen/Core>
#include <ros/ros.h>

namespace nav{
namespace mil_vision{

template<typename T = float>
class CameraModel{
Expand Down Expand Up @@ -59,4 +59,4 @@ Eigen::Matrix<T, 3, 4> CameraModel<T>::get_projection_matrix()
return K * R * aug;
}

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <iostream>


namespace nav
namespace mil_vision
{

template<typename img_scalar_t = uint8_t, typename float_t = float>
Expand Down Expand Up @@ -130,7 +130,7 @@ class ROSCameraStream : public CameraFrameSequence<std::shared_ptr<image_geometr
// Shared CameraFrame properties if camera geometry is constant
int COLS = -1;
int ROWS = -1;
nav::PixelType TYPE = nav::PixelType::_UNKNOWN;
mil_vision::PixelType TYPE = mil_vision::PixelType::_UNKNOWN;

// Mutex for multithreaded access to camera frame data
std::mutex _mtx;
Expand Down Expand Up @@ -168,7 +168,7 @@ class ROSCameraStream : public CameraFrameSequence<std::shared_ptr<image_geometr
template<typename img_scalar_t, typename float_t>
bool ROSCameraStream<img_scalar_t, float_t>::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;
Expand Down Expand Up @@ -237,7 +237,7 @@ template<typename img_scalar_t, typename float_t>
typename ROSCameraStream<img_scalar_t, float_t>::CamFrameConstPtr
ROSCameraStream<img_scalar_t, float_t>::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)
Expand Down Expand Up @@ -269,7 +269,7 @@ template<typename img_scalar_t, typename float_t>
typename ROSCameraStream<img_scalar_t, float_t>::CamFrameConstPtr
ROSCameraStream<img_scalar_t, float_t>::operator[](int i)
{
using mil::tools::operator "" _s;
using mil_tools::operator "" _s;

// Prevent adding new frames while frames are being accessed
_mtx.lock();
Expand Down Expand Up @@ -337,4 +337,4 @@ ROSCameraStream<img_scalar_t, float_t>::~ROSCameraStream()
_cb_queue.disable();
}

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

#include <mil_tools/mil_tools.hpp>

namespace nav
namespace mil_vision
{

/*
Expand Down Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include <functional>


namespace nav{
namespace mil_vision{

template <typename output_T = pcl::PointXYZ, typename input_T = pcl::PointXYZ>
class PcdSubPubAlgorithm{
Expand Down Expand Up @@ -78,4 +78,4 @@ class PcdSubPubAlgorithm{
std::string _err_msg;
};

} //namespace nav
} //namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include <pcl_ros/point_cloud.h>
#include <pcl_ros/transforms.h>

namespace nav{
namespace mil_vision {

class PcdSubPubAlgorithm{
/*
Expand Down Expand Up @@ -67,4 +67,4 @@ class PcdColorizer : public PcdSubPubAlgorithm{
sensor_msgs::CameraInfoConstPtr latest_frame_info_msg;
};

} // namwspace nav
} // namwspace nav
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include "ros/ros.h"
#include "geometry_msgs/Pose.h"

namespace nav {
namespace mil_vision {

// ******* 3D Visualization *******
class RvizVisualizer {
Expand Down
2 changes: 1 addition & 1 deletion perception/mil_vision/nodes/camera_stream_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<cv::Vec3b> left_cam_stream(nh, history_length); // Constructs empty inactive
mil_vision::ROSCameraStream<cv::Vec3b> 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
Expand Down
8 changes: 4 additions & 4 deletions perception/mil_vision/src/mil_vision_lib/active_contours.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
using namespace std;
using namespace cv;

namespace nav
namespace mil_vision
{

namespace Perturbations
Expand Down Expand Up @@ -226,7 +226,7 @@ bool ClosedCurve::validateCurve(std::vector<cv::Point2i>& 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;
}
Expand All @@ -236,7 +236,7 @@ bool ClosedCurve::validateCurve(std::vector<cv::Point2i>& 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;
}
Expand All @@ -250,4 +250,4 @@ vector<float> calcCosts(const Mat& img, vector<ClosedCurve::Perturbation> candid

}

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#include <colorizer/camera_observer.hpp>

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}
Expand Down Expand Up @@ -70,4 +70,4 @@ ColorObservation::VecImg CameraObserver::get_color_observations(const PCD<pcl::P

}

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include <colorizer/color_observation.hpp>


namespace nav{
namespace mil_vision{

UnoccludedPointsImg::UnoccludedPointsImg()
// : frame_ptr(frame_ptr),
Expand All @@ -12,4 +12,4 @@ UnoccludedPointsImg::UnoccludedPointsImg()

}

} // namespace nav
} // namespace mil_vision
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down Expand Up @@ -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 (";
Expand Down Expand Up @@ -170,4 +170,4 @@ void PcdColorizer::_cloud_cb(const PCD<>::ConstPtr &cloud_in)

// }

} // namespace nav
} // namespace mil_vision
Loading

0 comments on commit 9ab1f95

Please sign in to comment.