Skip to content

Commit

Permalink
update technical report
Browse files Browse the repository at this point in the history
  • Loading branch information
qintonguav committed Jun 19, 2017
1 parent c0edd92 commit 67ba02e
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 7 deletions.
8 changes: 2 additions & 6 deletions ar_demo/launch/ar_A3.launch
Original file line number Diff line number Diff line change
@@ -1,16 +1,12 @@
<launch>

<!-- <include file="$(find vins_estimator)/launch/A3.launch"/>
-->
<include file="$(find vins_estimator)/launch/A3.launch"/>

<node pkg="ar_demo" type="ar_demo_node" name="ar_demo_node" output="screen">
<remap from="~image_raw" to="/djiros/image"/>
<remap from="~camera_pose" to="/vins_estimator/camera_pose"/>
<remap from="~pointcloud" to="/vins_estimator/point_cloud"/>
<param name="calib_file" type="string" value="$(find feature_tracker)/../config/A3/A3_config.yaml"/>
<param name="use_undistored_img" type="bool" value="false"/>
</node>

<!--
<node name="rvizvisualisation" pkg="rviz" type="rviz" output="log" args="-d $(find ar_demo)/config/AR_demo.rviz" />
-->
</launch>
Binary file modified support_files/paper/tro_technical_report.pdf
Binary file not shown.
3 changes: 2 additions & 1 deletion vins_estimator/src/estimator_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,8 @@ void imu_callback(const sensor_msgs::ImuConstPtr &imu_msg)
predict(imu_msg);
std_msgs::Header header = imu_msg->header;
header.frame_id = "world";
pubLatestOdometry(tmp_P, tmp_Q, tmp_V, header);
if (estimator.solver_flag == Estimator::SolverFlag::NON_LINEAR)
pubLatestOdometry(tmp_P, tmp_Q, tmp_V, header);
}
}

Expand Down

0 comments on commit 67ba02e

Please sign in to comment.