diff --git a/CMakeLists.txt b/CMakeLists.txt
index 84ee585..543a3f7 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -53,7 +53,7 @@ find_package(Boost REQUIRED COMPONENTS system filesystem)
if(BUILD_ROS_NODE)
find_package(catkin REQUIRED COMPONENTS
- roscpp roslib cmake_modules svo_msgs)
+ roscpp roslib cmake_modules svo_msgs cv_bridge)
catkin_package(
DEPENDS OpenCV Eigen Boost
CATKIN_DEPENDS roscpp roslib svo_msgs
diff --git a/include/rmd/depthmap_node.h b/include/rmd/depthmap_node.h
index 84a05de..41723aa 100644
--- a/include/rmd/depthmap_node.h
+++ b/include/rmd/depthmap_node.h
@@ -26,11 +26,25 @@
namespace rmd
{
+namespace ProcessingStates
+{
+enum State
+{
+ UPDATE,
+ TAKE_REFERENCE_FRAME,
+};
+}
+typedef ProcessingStates::State State;
+
class DepthmapNode
{
public:
+ DepthmapNode();
void denseInputCallback(
const svo_msgs::DenseInputConstPtr &dense_input);
+private:
+ rmd::Depthmap depthmap_;
+ State state_;
};
} // rmd namespace
diff --git a/package.xml b/package.xml
index fee3f6e..ef28058 100644
--- a/package.xml
+++ b/package.xml
@@ -17,10 +17,12 @@
roscpp
roslib
svo_msgs
+ cv_bridge
roscpp
roslib
svo_msgs
+ cv_bridge
diff --git a/src/depthmap_node.cpp b/src/depthmap_node.cpp
index 7af333a..d2d9bc5 100644
--- a/src/depthmap_node.cpp
+++ b/src/depthmap_node.cpp
@@ -15,10 +15,63 @@
// You should have received a copy of the GNU General Public License
// along with this program. If not, see .
+#include
+#include
+#include
+
#include
+#include
+
+rmd::DepthmapNode::DepthmapNode()
+ : depthmap_(752, 480, 481.2f, 319.5f, -480.0f, 239.5f)
+{
+ state_ = rmd::State::TAKE_REFERENCE_FRAME;
+}
void rmd::DepthmapNode::denseInputCallback(
const svo_msgs::DenseInputConstPtr &dense_input)
{
- std::cout << "svo msg received" << std::endl;
+ cv::Mat img_8uC1;
+ try
+ {
+ img_8uC1 = cv_bridge::toCvCopy(
+ dense_input->image,
+ sensor_msgs::image_encodings::MONO8)->image;
+ }
+ catch (cv_bridge::Exception& e)
+ {
+ ROS_ERROR("cv_bridge exception: %s", e.what());
+ }
+ rmd::SE3 T_world_curr(
+ dense_input->pose.orientation.w,
+ dense_input->pose.orientation.x,
+ dense_input->pose.orientation.y,
+ dense_input->pose.orientation.z,
+ dense_input->pose.position.x,
+ dense_input->pose.position.y,
+ dense_input->pose.position.z);
+
+ switch (state_) {
+ case rmd::State::TAKE_REFERENCE_FRAME:
+ if(depthmap_.setReferenceImage(
+ img_8uC1,
+ T_world_curr.inv(),
+ dense_input->min_depth,
+ dense_input->max_depth))
+ {
+ state_ = State::UPDATE;
+ }
+ else
+ {
+ std::cerr << "ERROR: could not set reference image" << std::endl;
+ }
+ break;
+ case rmd::State::UPDATE:
+ depthmap_.update(img_8uC1, T_world_curr.inv());
+ break;
+ default:
+ break;
+ }
+
}
+