diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz b/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz index 4d001c9..7b09bdd 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/rviz/mynteye.rviz @@ -32,6 +32,8 @@ Panels: Name: Time SyncMode: 0 SyncSource: Points +Toolbars: + toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -56,7 +58,7 @@ Visualization Manager: - Class: rviz/Group Displays: - Class: rviz/Image - Enabled: true + Enabled: false Image Topic: /mynteye/left/image_raw Max Value: 1 Median window: 5 @@ -66,7 +68,7 @@ Visualization Manager: Queue Size: 1 Transport Hint: raw Unreliable: false - Value: true + Value: false - Class: rviz/Image Enabled: false Image Topic: /mynteye/right/image_raw @@ -152,10 +154,10 @@ Visualization Manager: - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 6.22900009 + Max Value: 1.98300004 Min Value: 0 Value: true - Axis: Z + Axis: X Channel Name: intensity Class: rviz/PointCloud2 Color: 255; 255; 255 @@ -221,7 +223,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 14.7952175 + Distance: 2.80799317 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 @@ -236,10 +238,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 - Pitch: -1.46479619 + Pitch: 0.520203829 Target Frame: Value: Orbit (rviz) - Yaw: 1.54539752 + Yaw: 4.3935833 Saved: ~ Window Geometry: Depth: @@ -257,7 +259,7 @@ Window Geometry: collapsed: false LeftRect: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Right: collapsed: false RightRect: diff --git a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc index c7c94f2..6e86dc2 100644 --- a/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc +++ b/wrappers/ros/src/mynt_eye_ros_wrapper/src/wrapper_nodelet.cc @@ -849,9 +849,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet { for (std::size_t x = 0; x < in->width; ++x) { auto &&point = data.frame.at(y, x); - *iter_x = point[0] * 0.001; - *iter_y = point[1] * 0.001; - *iter_z = point[2] * 0.001; + *iter_x = point[2] * 0.001; + *iter_y = 0.f - point[0] * 0.001; + *iter_z = 0.f - point[1] * 0.001; *iter_r = static_cast(255); *iter_g = static_cast(255); @@ -1212,10 +1212,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet { mesh_msg_.header.stamp = ros::Time::now(); mesh_msg_.type = visualization_msgs::Marker::MESH_RESOURCE; // fill orientation - mesh_msg_.pose.orientation.x = 0; - mesh_msg_.pose.orientation.y = 0; - mesh_msg_.pose.orientation.z = 0; - mesh_msg_.pose.orientation.w = 0; + mesh_msg_.pose.orientation.x = 1; + mesh_msg_.pose.orientation.y = 1; + mesh_msg_.pose.orientation.z = 1; + mesh_msg_.pose.orientation.w = 1; // fill position mesh_msg_.pose.position.x = 0;