Skip to content

Commit 33bf8a5

Browse files
authored
Merge pull request #92 from NVIDIA-ISAAC-ROS/hotfix-release-dp3.1-1
Update validation instructions and transform
2 parents ce92eb5 + f53c328 commit 33bf8a5

File tree

3 files changed

+36
-15
lines changed

3 files changed

+36
-15
lines changed

docs/validating-cuvslam-setup.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -185,14 +185,15 @@ The purpose of this test is to validate that the system is able to appropriately
185185
186186
> **Note**: To maximize the accuracy of this test, ensure that dynamic obstacles are removed from the robot's field of view. If a nontrivial dynamic obstacle is introduced while the robot is performing the loop, please restart this test.
187187

188-
4. As the camera nears the completion of its first lap, place the camera at rest, taking care to precisely align it with the floor marker indicating the starting pose.
189-
5. On the standalone computer and within the RViz window, ensure that a nontrivial number of visual features now appear red. Additionally, ensure that the camera frame appears nearly coincident with the `/map` frame.
188+
4. As the camera nears the completion of its first lap, move the camera in a small circle of radius ~0.5m around the origin of the starting pose. This step helps ensure that the previously-seen visual features are recognized and matched.
189+
5. Place the camera at rest, taking care to precisely align it with the floor marker indicating the starting pose.
190+
6. On the standalone computer and within the RViz window, ensure that a nontrivial number of visual features now appear red. Additionally, ensure that the camera frame appears nearly coincident with the `/map` frame.
190191

191192
> **Note**: It is acceptable for the `/odom` frame to jump around significantly with respect to the `/map` frame. For the purposes of this test, only the transform between the `/map` and camera frames is relevant. For additional information about the design intent behind these frames, please see [REP-0105](https://www.ros.org/reps/rep-0105.html).
192193

193194
<div align="center"><img src="../resources/validation_test2_rviz.png" width="600px"/></div>
194195

195-
6. On the standalone computer and within the `tf2_echo` terminal, note the latest transform reported between `/map` and the appropriate camera frame.
196+
7. On the standalone computer and within the `tf2_echo` terminal, note the latest transform reported between `/map` and the appropriate camera frame.
196197
<div align="center"><img src="../resources/validation_test2_tf2.png" width="600px"/></div>
197198

198199
1. Validate Orientation:

isaac_ros_visual_slam/include/isaac_ros_visual_slam/impl/visual_slam_impl.hpp

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -139,15 +139,25 @@ struct VisualSlamNode::VisualSlamImpl
139139
std::array<float, kMaxNumCameraParameters> left_intrinsics;
140140
std::array<float, kMaxNumCameraParameters> right_intrinsics;
141141
// Transformation converting from
142-
// ROS Frame (x-forward, y-left, z-up) to
142+
// ROS Frame (x-forward, y-left, z-up) to
143143
// cuVSLAM Frame (x-right, y-up, z-backward)
144144
const tf2::Transform cuvslam_pose_base_link;
145145

146146
// Transformation converting from
147147
// cuVSLAM Frame (x-right, y-up, z-backward) to
148-
// ROS Frame (x-forward, y-left, z-up)
148+
// ROS Frame (x-forward, y-left, z-up)
149149
const tf2::Transform base_link_pose_cuvslam;
150150

151+
// Transformation converting from
152+
// Optical Frame (x-right, y-down, z-forward) to
153+
// cuVSLAM Frame (x-right, y-up, z-backward)
154+
const tf2::Transform cuvslam_pose_optical;
155+
156+
// Transformation converting from
157+
// cuVSLAM Frame (x-right, y-up, z-backward) to
158+
// Optical Frame (x-right, y-down, z-forward)
159+
const tf2::Transform optical_pose_cuvslam;
160+
151161
// Start pose of visual odometry
152162
tf2::Transform start_odom_pose = tf2::Transform::getIdentity();
153163

isaac_ros_visual_slam/src/impl/visual_slam_impl.cpp

Lines changed: 20 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -92,16 +92,27 @@ VisualSlamNode::VisualSlamImpl::VisualSlamImpl(VisualSlamNode & node)
9292
: logger_name(std::string(node.get_logger().get_name())),
9393
node_clock(node.get_clock()),
9494
// Set cuvslam_pose_base_link for converting ROS coordinate to cuVSLAM coordinate
95-
// ROS -> cuVSLAM
96-
// x -> -z
97-
// y -> -x
98-
// z -> y
95+
// ROS -> cuVSLAM
96+
// x -> -z
97+
// y -> -x
98+
// z -> y
9999
cuvslam_pose_base_link(tf2::Matrix3x3(
100100
0, -1, 0,
101101
0, 0, 1,
102102
-1, 0, 0
103103
)),
104104
base_link_pose_cuvslam(cuvslam_pose_base_link.inverse()),
105+
// Set cuvslam_pose_optical for converting Optical coordinate to cuVSLAM coordinate
106+
// Optical -> cuVSLAM
107+
// x -> x
108+
// y -> -y
109+
// z -> -z
110+
cuvslam_pose_optical(tf2::Matrix3x3(
111+
1, 0, 0,
112+
0, -1, 0,
113+
0, 0, -1
114+
)),
115+
optical_pose_cuvslam(cuvslam_pose_optical.inverse()),
105116
tf_buffer(std::make_unique<tf2_ros::Buffer>(node_clock)),
106117
tf_listener(std::make_shared<tf2_ros::TransformListener>(*tf_buffer)),
107118
tf_publisher(std::make_unique<tf2_ros::TransformBroadcaster>(&node)),
@@ -225,11 +236,9 @@ void VisualSlamNode::VisualSlamImpl::Init(
225236
tf2::Transform left_rect_pose_right_rect(left_pose_right);
226237
tf2::Transform left_rect_pose_left_unrect(left_r_mat);
227238
tf2::Transform right_rect_pose_right_unrect(right_r_mat);
228-
left_pose_right =
229-
left_rect_pose_left_unrect.inverse() * left_rect_pose_right_rect *
230-
right_rect_pose_right_unrect;
231-
// Invert transform for cuVSLAM for unrectified case.
232-
left_pose_right.setBasis(left_pose_right.getBasis().inverse());
239+
left_pose_right = ChangeBasis(
240+
cuvslam_pose_optical, (left_rect_pose_left_unrect.inverse() * left_rect_pose_right_rect *
241+
right_rect_pose_right_unrect));
233242
}
234243
}
235244

@@ -259,7 +268,8 @@ void VisualSlamNode::VisualSlamImpl::Init(
259268

260269
SetcuVSLAMCameraPose(
261270
cuvslam_cameras[LEFT_CAMERA_IDX], TocuVSLAMPose(tf2::Transform::getIdentity()));
262-
SetcuVSLAMCameraPose(cuvslam_cameras[RIGHT_CAMERA_IDX], TocuVSLAMPose(left_pose_right));
271+
SetcuVSLAMCameraPose(
272+
cuvslam_cameras[RIGHT_CAMERA_IDX], TocuVSLAMPose(left_pose_right));
263273

264274
cuvslam_cameras[LEFT_CAMERA_IDX].parameters = left_intrinsics.data();
265275
cuvslam_cameras[RIGHT_CAMERA_IDX].parameters = right_intrinsics.data();

0 commit comments

Comments
 (0)