diff --git a/manycal/include/manycal/Registrations.h b/manycal/include/manycal/Registrations.h index 7954b45..de07312 100644 --- a/manycal/include/manycal/Registrations.h +++ b/manycal/include/manycal/Registrations.h @@ -178,6 +178,7 @@ class TargetRegistration : public RegistrationBase ros::Subscriber _odomSub; ros::Time _lastTime; + bool _enableOdomPrior; bool _isOdomInitialized; VelocityIntegratorSE3 _velocityIntegrator; PoseSE3::CovarianceMatrix _odomOffset; diff --git a/manycal/src/Registrations.cpp b/manycal/src/Registrations.cpp index 60d4941..9e6722b 100644 --- a/manycal/src/Registrations.cpp +++ b/manycal/src/Registrations.cpp @@ -38,12 +38,14 @@ TargetRegistration::TargetRegistration( const std::string& n, GetParamRequired( ph, "odom_topic", topic ); GetParam( ph, "odom_cov_offset", _odomOffset, PoseSE3::CovarianceMatrix::Zero() ); + GetParam( ph, "enable_odom_prior", _enableOdomPrior, false); + _odomSub = nh.subscribe( topic, - buffLen, - &TargetRegistration::OdometryCallback, - this ); + buffLen, + &TargetRegistration::OdometryCallback, + this ); ROS_INFO_STREAM( "Target: " << _name << " subscribing to odometry on " - << topic ); + << topic ); _poses = std::make_shared( _graph, _optimizePose ); } @@ -209,10 +211,24 @@ bool TargetRegistration::IsPoseInitialized( const ros::Time& time ) const void TargetRegistration::OdometryCallback( const nav_msgs::Odometry::ConstPtr& msg ) { - PoseSE3::TangentVector vel = MsgToTangent( msg->twist.twist ); - PoseSE3::CovarianceMatrix cov; - ParseMatrix( msg->twist.covariance, cov ); // TODO Check return? - _velocityIntegrator.BufferInfo( msg->header.stamp.toSec(), vel, cov ); + if(_enableOdomPrior) + { + ros::Time time = msg->header.stamp; + PoseSE3 prior = MsgToPose( msg->pose.pose ); + PoseSE3::CovarianceMatrix cov; + ParseMatrix ( msg->pose.covariance, cov ); + + isam::PoseSE3 p = PoseToIsam( prior ); + _poses->CreatePrior( time, p, isam::Covariance( cov ) ); + + } + else + { + PoseSE3::TangentVector vel = MsgToTangent( msg->twist.twist ); + PoseSE3::CovarianceMatrix cov; + ParseMatrix( msg->twist.covariance, cov ); // TODO Check return? + _velocityIntegrator.BufferInfo( msg->header.stamp.toSec(), vel, cov ); + } } ExtrinsicsRegistration::ExtrinsicsRegistration( TargetRegistration& p,