added minor visualization changes
This commit is contained in:
		@@ -1836,12 +1836,22 @@ void MsckfVio::publish(const ros::Time& time) {
 | 
			
		||||
  Eigen::Vector3d body_velocity =
 | 
			
		||||
    IMUState::T_imu_body.linear() * imu_state.velocity;
 | 
			
		||||
 | 
			
		||||
  // Generate camera frame form IMU Frame
 | 
			
		||||
  Eigen::Isometry3d T_i_c = Eigen::Isometry3d::Identity();
 | 
			
		||||
  T_i_c.linear() =  imu_state.R_imu_cam0;
 | 
			
		||||
  T_i_c.translation() = imu_state.t_cam0_imu;
 | 
			
		||||
 | 
			
		||||
  // Publish tf
 | 
			
		||||
  if (publish_tf) {
 | 
			
		||||
    tf::Transform T_b_w_tf;
 | 
			
		||||
    tf::transformEigenToTF(T_b_w, T_b_w_tf);
 | 
			
		||||
    tf_pub.sendTransform(tf::StampedTransform(
 | 
			
		||||
          T_b_w_tf, time, fixed_frame_id, child_frame_id));
 | 
			
		||||
 | 
			
		||||
    tf::Transform T_i_c_tf;
 | 
			
		||||
    tf::transformEigenToTF(T_i_c, T_i_c_tf);
 | 
			
		||||
    tf_pub.sendTransform(tf::StampedTransform(
 | 
			
		||||
          T_i_c_tf, time, child_frame_id, "camera"));
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  // Publish the odometry
 | 
			
		||||
 
 | 
			
		||||
		Reference in New Issue
	
	Block a user