Skip to content

Commit

Permalink
removed build of monoxcal, added dynamic reconfigure to grid finder, …
Browse files Browse the repository at this point in the history
…fixed issues with opencv3 ros-industrial#89
  • Loading branch information
drchrislewis committed Mar 21, 2017
1 parent d35d389 commit f8182e2
Show file tree
Hide file tree
Showing 9 changed files with 388 additions and 322 deletions.
14 changes: 10 additions & 4 deletions industrial_extrinsic_cal/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ find_package(catkin REQUIRED COMPONENTS
std_srvs
tf
tf_conversions
dynamic_reconfigure
)

find_package(Boost REQUIRED)
Expand All @@ -29,6 +30,9 @@ message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
find_package(OpenCV REQUIRED)
message("-- Found OpenCV version ${OpenCV_VERSION}: ${OpenCV_INCLUDE_DIRS}")




find_package(PkgConfig REQUIRED)
pkg_check_modules(yaml_cpp REQUIRED yaml-cpp)
if(NOT ${yaml_cpp_VERSION} VERSION_LESS "0.5")
Expand Down Expand Up @@ -83,6 +87,10 @@ generate_messages(
std_msgs
)

generate_dynamic_reconfigure_options(
cfg/circle_grid_finder.cfg
)


catkin_package(
LIBRARIES
Expand Down Expand Up @@ -142,7 +150,8 @@ add_library(
src/target.cpp
src/targets_yaml_parser.cpp
)
add_dependencies(industrial_extrinsic_cal ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
add_dependencies(industrial_extrinsic_cal ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg)

target_link_libraries(
industrial_extrinsic_cal

Expand All @@ -156,7 +165,6 @@ target_link_libraries(
# targets: other nodes
add_executable(camera_observer_scene_trigger src/nodes/camera_observer_scene_trigger.cpp)
add_executable(manual_calt_adjust src/nodes/manual_calt_adjuster.cpp)
add_executable(mono_ex_cal src/nodes/mono_ex_cal.cpp)
add_executable(mutable_joint_state_publisher src/nodes/mutable_joint_state_publisher.cpp)
add_executable(nist_analysis src/nodes/nist_analysis.cpp)
add_executable(ros_robot_trigger_action_service src/nodes/ros_robot_scene_trigger_action_server.cpp)
Expand All @@ -171,7 +179,6 @@ add_dependencies(trigger_service ${catkin_EXPORTED_TARGETS} ${i

target_link_libraries(camera_observer_scene_trigger industrial_extrinsic_cal ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY} ${CERES_LIBRARIES})
target_link_libraries(manual_calt_adjust industrial_extrinsic_cal ${catkin_LIBRARIES})
target_link_libraries(mono_ex_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES})
target_link_libraries(mutable_joint_state_publisher ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY})
target_link_libraries(nist_analysis industrial_extrinsic_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES})
target_link_libraries(ros_robot_trigger_action_service ${catkin_LIBRARIES})
Expand All @@ -185,7 +192,6 @@ install(
camera_observer_scene_trigger
industrial_extrinsic_cal
manual_calt_adjust
mono_ex_cal
mutable_joint_state_publisher
nist_analysis
ros_robot_trigger_action_service
Expand Down
19 changes: 19 additions & 0 deletions industrial_extrinsic_cal/cfg/circle_grid_finder.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
#!/usr/bin/env python
PACKAGE = "industrial_extrinsic_cal"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()


gen.add("filter_by_area", bool_t, 0, "filter blobs by their area", True)
gen.add("filter_by_circularity", bool_t, 0, "filter blobs by their circularity", False)
gen.add("min_area", int_t, 0, "Minimum area of a blob", 1, 25, 5000)
gen.add("max_area", int_t, 0, "Maximum area of a blob", 1, 5000, 10000)
gen.add("min_circularity", double_t, 0, "The min aspect ratio necessary to be a circlular blob", .1, .8, 3.402823e38)
gen.add("max_circularity", double_t, 0, "The max aspect ratio necessary to be a circlular blob", .1, 3.402823e38, 3.402823e38)
gen.add("min_threshold", int_t, 0, "The contrast minimum threshold to be a blob", 1, 50, 1000)
gen.add("max_threshold", int_t, 0, "The contrast maximum threshold to be a blob", 1, 500, 1000)
gen.add("min_distance", double_t, 0, "The min distance between blobs", 1.0, 5.0, 500)

exit(gen.generate(PACKAGE, "industrial_extrinsic_cal_node", "circle_grid_finder"))
Original file line number Diff line number Diff line change
Expand Up @@ -86,23 +86,9 @@ class CV_EXPORTS_W CircleDetector : public FeatureDetector
void write( FileStorage& fs ) const;
};

CV_WRAP CircleDetector(const CircleDetector::Params &parameters = CircleDetector::Params());
CV_WRAP static Ptr<CircleDetector>
create(const CircleDetector::Params &parameters = CircleDetector::Params());

virtual void read( const FileNode& fn );
virtual void write( FileStorage& fs ) const;

protected:
struct CV_EXPORTS Center
{
Point2d location;
double radius;
double confidence;
};

virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
virtual void findCircles(const Mat &image, const Mat &binaryImage, vector<Center> &centers) const;

Params params;
};
}
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <industrial_extrinsic_cal/camera_observer.hpp>
#include <industrial_extrinsic_cal/basic_types.h>
#include <industrial_extrinsic_cal/ceres_costs_utils.h>
#include <dynamic_reconfigure/server.h>
#include <industrial_extrinsic_cal/circle_grid_finderConfig.h>

#include <iostream>
#include <sstream>
Expand All @@ -41,7 +43,7 @@
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/SetCameraInfo.h>
#include <geometry_msgs/PointStamped.h>

#include <industrial_extrinsic_cal/circle_detector.hpp>

/**
* @brief enumerator containing three options for the type of pattern to detect
Expand Down Expand Up @@ -208,7 +210,12 @@ namespace industrial_extrinsic_cal
/**
* @brief circle_detector_ptr_ is a custom blob detector which localizes circles better than simple blob detection
*/
cv::Ptr<cv::FeatureDetector> circle_detector_ptr_;
cv::Ptr<cv::CircleDetector> circle_detector_ptr_;

/**
* @brief blob_detector_ptr_ is a simple blob detector
*/
cv::Ptr<cv::FeatureDetector> blob_detector_ptr_;

/**
* @brief new_image_collected, set after the trigger is done
Expand Down Expand Up @@ -291,15 +298,23 @@ namespace industrial_extrinsic_cal
bool pullCameraInfo(double &fx, double &fy, double &cx, double &cy, double &k1, double &k2, double &k3, double &p1, double &p2,
int &width, int &height);

void dynReConfCallBack(industrial_extrinsic_cal::circle_grid_finderConfig &config, uint32_t level);

private:

int image_number_; /**< a counter of images recieved */
cv::Mat last_raw_image_; /**< the image last received */
bool use_circle_detector_;
bool white_blobs_;
ros::ServiceClient client_;
sensor_msgs::SetCameraInfo srv_;
ros::NodeHandle *rnh_;
dynamic_reconfigure::Server<industrial_extrinsic_cal::circle_grid_finderConfig> *server_;

};


} //end industrial_extrinsic_cal namespace


#endif /* ROS_CAMERA_OBSERVER_H_ */
2 changes: 1 addition & 1 deletion industrial_extrinsic_cal/src/camera_yaml_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ namespace industrial_extrinsic_cal {
else{
temp_camera->pullTransform();
}
temp_camera->camera_observer_ = boost::make_shared<ROSCameraObserver>(temp_topic);
temp_camera->camera_observer_ = boost::make_shared<ROSCameraObserver>(temp_topic, temp_name);
}
catch (YAML::ParserException& e){
ROS_INFO_STREAM("Failed to read in moving cameras from yaml file ");
Expand Down
3 changes: 3 additions & 0 deletions industrial_extrinsic_cal/src/ceres_blocks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -453,6 +453,9 @@ bool CeresBlocks::writeAllStaticTransforms(string filePath)
return false;
}//end if writing to file
outputFile << "<launch>\n";
outputFile << "# this file might be empty\n";
outputFile << "# It might contain static transform publishers that were updated through calibration\n";
outputFile << "# Often, transform interfaces use some other mechanism to update themselves\n";
outputFile.close();

bool rtn = true;
Expand Down
Loading

0 comments on commit f8182e2

Please sign in to comment.