Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions include/Tracking.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "MapPublisher.h"

#include<tf/transform_broadcaster.h>
#include "geometry_msgs/PoseStamped.h"


namespace ORB_SLAM
Expand Down Expand Up @@ -180,6 +181,10 @@ class Tracking

// Transfor broadcaster (for visualization in rviz)
tf::TransformBroadcaster mTfBr;

// Pose broadcaster
ros::NodeHandle n;
ros::Publisher PosPub = n.advertise<geometry_msgs::PoseStamped>("ORB_SLAM/pose", 5);
};

} //namespace ORB_SLAM
Expand Down
15 changes: 15 additions & 0 deletions src/Tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@
#include<fstream>




using namespace std;

namespace ORB_SLAM
Expand Down Expand Up @@ -312,6 +314,19 @@ void Tracking::GrabImage(const sensor_msgs::ImageConstPtr& msg)
tf::Transform tfTcw(M,V);

mTfBr.sendTransform(tf::StampedTransform(tfTcw,ros::Time::now(), "ORB_SLAM/World", "ORB_SLAM/Camera"));

geometry_msgs::PoseStamped poseMSG;
poseMSG.pose.position.x = tfTcw.getOrigin().x();
poseMSG.pose.position.y = tfTcw.getOrigin().y();
poseMSG.pose.position.z = tfTcw.getOrigin().z();
poseMSG.pose.orientation.x = tfTcw.getRotation().x();
poseMSG.pose.orientation.y = tfTcw.getRotation().y();
poseMSG.pose.orientation.z = tfTcw.getRotation().z();
poseMSG.pose.orientation.w = tfTcw.getRotation().w();
poseMSG.header.frame_id = "VSLAM";
poseMSG.header.stamp = ros::Time::now();
PosPub.publish(poseMSG);

}

}
Expand Down