diff --git a/launch/odometry_eval.launch b/launch/odometry_eval.launch index 7f90726..3d28804 100644 --- a/launch/odometry_eval.launch +++ b/launch/odometry_eval.launch @@ -12,8 +12,10 @@ + + diff --git a/launch/slam_eval.launch b/launch/slam_eval.launch index c1ffebd..07d0fd4 100644 --- a/launch/slam_eval.launch +++ b/launch/slam_eval.launch @@ -13,8 +13,10 @@ + + diff --git a/launch/slam_eval_kitti.launch b/launch/slam_eval_kitti.launch index 1ba6bda..1ab2039 100644 --- a/launch/slam_eval_kitti.launch +++ b/launch/slam_eval_kitti.launch @@ -13,8 +13,10 @@ + + diff --git a/src/ros/odometry_eval.cc b/src/ros/odometry_eval.cc index a9b0153..8d481a6 100644 --- a/src/ros/odometry_eval.cc +++ b/src/ros/odometry_eval.cc @@ -44,16 +44,22 @@ void OdometryEval::InitPublishers() { TrackingEval::InitPublishers(); string outputTopic; + string outputOptTopic; string outputGndTopic; string outputPathTopic; + string outputPathOptTopic; string outputPathGndTopic; this->nhp_.param("odometry_estimate_topic", outputTopic, string("/omni_slam/odometry")); + this->nhp_.param("odometry_optimized_topic", outputOptTopic, string("/omni_slam/odometry_optimized")); this->nhp_.param("odometry_ground_truth_topic", outputGndTopic, string("/omni_slam/odometry_truth")); this->nhp_.param("path_estimate_topic", outputPathTopic, string("/omni_slam/odometry_path")); + this->nhp_.param("path_optimized_topic", outputOptTopic, string("/omni_slam/odometry_path_optimized")); this->nhp_.param("path_ground_truth_topic", outputPathGndTopic, string("/omni_slam/odometry_path_truth")); odometryPublisher_ = this->nh_.template advertise(outputTopic, 2); + odometryOptPublisher_ = this->nh_.template advertise(outputOptTopic, 2); odometryGndPublisher_ = this->nh_.template advertise(outputGndTopic, 2); pathPublisher_ = this->nh_.template advertise(outputPathTopic, 2); + pathOptPublisher_ = this->nh_.template advertise(outputPathOptTopic, 2); pathGndPublisher_ = this->nh_.template advertise(outputPathGndTopic, 2); } @@ -72,7 +78,7 @@ void OdometryEval::Finish() { ROS_INFO("Performing bundle adjustment..."); odometryModule_->BundleAdjust(this->trackingModule_->GetLandmarks()); - PublishOdometry(); + PublishOdometry(true); } template @@ -89,7 +95,7 @@ void OdometryEval::Visualize(cv_bridge::CvImagePtr &base_img) } template -void OdometryEval::PublishOdometry() +void OdometryEval::PublishOdometry(bool optimized) { geometry_msgs::PoseStamped poseMsg; poseMsg.header.frame_id = cameraFrame_; @@ -105,7 +111,14 @@ void OdometryEval::PublishOdometry() poseMsg.pose.orientation.z = quat.normalized().z(); poseMsg.pose.orientation.w = quat.normalized().w(); poseMsg.header.stamp = ::ros::Time(this->trackingModule_->GetFrames().back()->GetTime()); - odometryPublisher_.publish(poseMsg); + if (optimized) + { + odometryOptPublisher_.publish(poseMsg); + } + else + { + odometryPublisher_.publish(poseMsg); + } } const Matrix &poseGnd = this->trackingModule_->GetFrames().back()->GetPose(); poseMsg.header.frame_id = cameraFrame_; @@ -163,7 +176,14 @@ void OdometryEval::PublishOdometry() } first = false; } - pathPublisher_.publish(path); + if (optimized) + { + pathOptPublisher_.publish(path); + } + else + { + pathPublisher_.publish(path); + } pathGndPublisher_.publish(pathGnd); } diff --git a/src/ros/odometry_eval.h b/src/ros/odometry_eval.h index 96a6c84..7f604b9 100644 --- a/src/ros/odometry_eval.h +++ b/src/ros/odometry_eval.h @@ -27,14 +27,16 @@ class OdometryEval : public virtual TrackingEval virtual void GetResultsData(std::map>> &data); virtual void Visualize(cv_bridge::CvImagePtr &base_img); - void PublishOdometry(); + void PublishOdometry(bool optimized = false); std::unique_ptr odometryModule_; private: ::ros::Publisher odometryPublisher_; + ::ros::Publisher odometryOptPublisher_; ::ros::Publisher odometryGndPublisher_; ::ros::Publisher pathPublisher_; + ::ros::Publisher pathOptPublisher_; ::ros::Publisher pathGndPublisher_; std::string cameraFrame_; diff --git a/src/ros/slam_eval.cc b/src/ros/slam_eval.cc index f2cfaef..54d5a37 100644 --- a/src/ros/slam_eval.cc +++ b/src/ros/slam_eval.cc @@ -55,7 +55,7 @@ void SLAMEval::ProcessFrame(unique_ptr &&frame) void SLAMEval::Finish() { ReconstructionEval::Finish(); - PublishOdometry(); + PublishOdometry(true); } void SLAMEval::GetResultsData(std::map>> &data)