Skip to content

Commit

Permalink
Corrected pose calculation error
Browse files Browse the repository at this point in the history
  • Loading branch information
ayushgaud committed Feb 13, 2017
2 parents fda667c + e62ad23 commit fd86254
Showing 1 changed file with 15 additions and 15 deletions.
30 changes: 15 additions & 15 deletions Examples/ROS/ORB_SLAM2/src/ros_mono.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,21 +86,21 @@ int main(int argc, char **argv)
void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
{
// Copy the ros image message to cv::Mat.
cv_bridge::CvImageConstPtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvShare(msg);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}

cv::Mat pose = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
if (pose.empty())
return;
//std::cout<<pose<<std::endl;
cv_bridge::CvImageConstPtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvShare(msg,sensor_msgs::image_encodings::MONO8);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}

cv::Mat pose = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
if (pose.empty())
return;
//std::cout<<pose<<std::endl;

/* global left handed coordinate system */
// static cv::Mat pose_prev = cv::Mat::eye(4,4, CV_32F);
Expand Down

0 comments on commit fd86254

Please sign in to comment.