5 #include <sparse_bundle_adjustment/Frame.h>
6 #include <visualization_msgs/Marker.h>
37 void addFrame(
const sba::Frame::ConstPtr& msg);
38 void addNode(
const sba::CameraNode& msg);
39 void addPoint(
const sba::WorldPoint& msg);
40 void addProj(
const sba::Projection& msg);
53 for (i=0; i < msg->nodes.size(); i++)
55 addNode(msg->nodes[i]);
59 for (i=0; i < msg->points.size(); i++)
61 addPoint(msg->points[i]);
65 for (i=0; i < msg->projections.size(); i++)
67 addProj(msg->projections[i]);
73 if (
sba.nodes.size() % 5 == 0)
80 printf(
"[SBA] Added frame with %u nodes, %u points, and %u projections (%f s)\n",
81 (
unsigned int)msg->nodes.size(), (
unsigned int)msg->points.size(),
82 (
unsigned int)msg->projections.size(), (end-beginning).toSec());
87 Vector4d trans(msg.transform.translation.x, msg.transform.translation.y, msg.transform.translation.z, 1.0);
88 Quaterniond qrot(msg.transform.rotation.w, msg.transform.rotation.x, msg.transform.rotation.y, msg.transform.rotation.z);
91 cam_params.
fx = msg.fx;
92 cam_params.
fy = msg.fy;
93 cam_params.
cx = msg.cx;
94 cam_params.
cy = msg.cy;
95 cam_params.
tx = msg.baseline;
97 bool fixed = msg.fixed;
99 unsigned int newindex =
sba.addNode(trans, qrot, cam_params, fixed);
101 node_indices[msg.index] = newindex;
106 Vector4d point(msg.x, msg.y, msg.z, msg.w);
107 unsigned int newindex =
sba.addPoint(point);
109 point_indices[msg.index] = newindex;
114 int camindex = node_indices[msg.camindex];
115 int pointindex = point_indices[msg.pointindex];
116 Vector3d keypoint(msg.u, msg.v, msg.d);
117 bool stereo = msg.stereo;
118 bool usecovariance = msg.usecovariance;
119 Eigen::Matrix3d covariance;
120 covariance << msg.covariance[0], msg.covariance[1], msg.covariance[2],
121 msg.covariance[3], msg.covariance[4], msg.covariance[5],
122 msg.covariance[6], msg.covariance[7], msg.covariance[8];
125 if (pointindex < (
int)
sba.tracks.size() && camindex < (
int)
sba.nodes.size())
127 sba.addProj(camindex, pointindex, keypoint, stereo);
129 sba.setProjCovariance(camindex, pointindex, covariance);
133 ROS_INFO(
"Failed to add projection: C: %d, P: %d, Csize: %d, Psize: %d",
134 camindex, pointindex,(
int)
sba.nodes.size(),(
int)
sba.tracks.size());
140 unsigned int projs = 0;
142 for (
int i = 0; i < (int)
sba.tracks.size(); i++)
144 projs +=
sba.tracks[i].projections.size();
146 ROS_INFO(
"SBA Nodes: %d, Points: %d, Projections: %d", (
int)
sba.nodes.size(),
147 (
int)
sba.tracks.size(), projs);
149 if (
sba.nodes.size() > 0)
154 double cost =
sba.calcRMSCost();
156 if (isnan(cost) || isinf(cost))
162 if (
sba.calcRMSCost() > 4.0)
164 if (
sba.calcRMSCost() > 4.0)
173 if (cam_marker_pub.getNumSubscribers() > 0 || point_marker_pub.getNumSubscribers() > 0)
182 cam_marker_pub = n.advertise<visualization_msgs::Marker>(
"/sba/cameras", 1);
183 point_marker_pub = n.advertise<visualization_msgs::Marker>(
"/sba/points", 1);
189 frame_sub = n.subscribe<sba::Frame>(
"/sba/frames", 5000, &
SBANode::addFrame,
this);
191 sba.useCholmod(
true);
193 printf(
"[SBA] Initialization complete.\n");
196 int main(
int argc,
char** argv)