feat: add mesh to rviz.
This commit is contained in:
parent
15464160f6
commit
98589a5753
|
@ -33,7 +33,7 @@
|
||||||
|
|
||||||
<arg name="gravity" default="9.8" />
|
<arg name="gravity" default="9.8" />
|
||||||
|
|
||||||
<arg name="mesh_file" default="S1030-0315.STL" />
|
<arg name="mesh_file" default="S1030-0315.obj" />
|
||||||
|
|
||||||
<!-- stream toggles -->
|
<!-- stream toggles -->
|
||||||
|
|
||||||
|
|
Binary file not shown.
130659
wrappers/ros/src/mynt_eye_ros_wrapper/mesh/S1030-0315.obj
Normal file
130659
wrappers/ros/src/mynt_eye_ros_wrapper/mesh/S1030-0315.obj
Normal file
File diff suppressed because it is too large
Load Diff
|
@ -9,6 +9,7 @@ Panels:
|
||||||
- /Images1
|
- /Images1
|
||||||
- /Images1/Rectified1
|
- /Images1/Rectified1
|
||||||
- /Disparity1
|
- /Disparity1
|
||||||
|
- /Marker1
|
||||||
Splitter Ratio: 0.5
|
Splitter Ratio: 0.5
|
||||||
Tree Height: 824
|
Tree Height: 824
|
||||||
- Class: rviz/Selection
|
- Class: rviz/Selection
|
||||||
|
@ -29,7 +30,7 @@ Panels:
|
||||||
Experimental: false
|
Experimental: false
|
||||||
Name: Time
|
Name: Time
|
||||||
SyncMode: 0
|
SyncMode: 0
|
||||||
SyncSource: Depth
|
SyncSource: Points
|
||||||
Visualization Manager:
|
Visualization Manager:
|
||||||
Class: ""
|
Class: ""
|
||||||
Displays:
|
Displays:
|
||||||
|
@ -133,10 +134,10 @@ Visualization Manager:
|
||||||
Transport Hint: raw
|
Transport Hint: raw
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Value: true
|
Value: true
|
||||||
Enabled: false
|
Enabled: true
|
||||||
Name: Disparity
|
Name: Disparity
|
||||||
- Class: rviz/Image
|
- Class: rviz/Image
|
||||||
Enabled: true
|
Enabled: false
|
||||||
Image Topic: /mynteye/depth/image_raw
|
Image Topic: /mynteye/depth/image_raw
|
||||||
Max Value: 1
|
Max Value: 1
|
||||||
Median window: 5
|
Median window: 5
|
||||||
|
@ -146,7 +147,7 @@ Visualization Manager:
|
||||||
Queue Size: 1
|
Queue Size: 1
|
||||||
Transport Hint: raw
|
Transport Hint: raw
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Value: true
|
Value: false
|
||||||
- Alpha: 1
|
- Alpha: 1
|
||||||
Autocompute Intensity Bounds: true
|
Autocompute Intensity Bounds: true
|
||||||
Autocompute Value Bounds:
|
Autocompute Value Bounds:
|
||||||
|
@ -186,6 +187,14 @@ Visualization Manager:
|
||||||
Topic: /mynteye/imu/data_raw
|
Topic: /mynteye/imu/data_raw
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Value: false
|
Value: false
|
||||||
|
- Class: rviz/Marker
|
||||||
|
Enabled: true
|
||||||
|
Marker Topic: /mynteye/camera_mesh
|
||||||
|
Name: Marker
|
||||||
|
Namespaces:
|
||||||
|
"": true
|
||||||
|
Queue Size: 100
|
||||||
|
Value: true
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Global Options:
|
Global Options:
|
||||||
Background Color: 48; 48; 48
|
Background Color: 48; 48; 48
|
||||||
|
@ -247,7 +256,7 @@ Window Geometry:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
LeftRect:
|
LeftRect:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
QMainWindow State: 000000ff00000000fd00000004000000000000026500000378fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000378000000d600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000008004c00650066007403000001bd000000860000024e00000190fb0000000a00520069006700680074030000038d000001dc0000025000000190fb00000010004c006500660074005200650063007402000001bd000002170000024e00000190fb00000012005200690067006800740052006500630074020000040c000002170000024f00000190fb0000000a0044006500700074006803000002160000024c0000024f00000190fb0000001200440069007300700061007200690074007902000001bd000002170000024e0000018ffb0000001a004400690073007000610072006900740079004e006f0072006d020000040c000002170000025100000190000000010000010f00000378fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000378000000ac00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003bf0000037800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
QMainWindow State: 000000ff00000000fd00000004000000000000026500000378fc020000000ffb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000378000000d600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000008004c00650066007403000001bd000000860000024e00000190fb0000000a00520069006700680074030000038d000001dc0000025000000190fb00000010004c006500660074005200650063007402000001bd000002170000024e00000190fb00000012005200690067006800740052006500630074020000040c000002170000024f00000190fb0000000a0044006500700074006802000002160000024c0000024f00000190fb0000001200440069007300700061007200690074007903000001bd000002170000024e0000018ffb0000001a004400690073007000610072006900740079004e006f0072006d030000040c000002170000025100000190000000010000010f00000378fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000378000000ac00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003bf0000037800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||||
Right:
|
Right:
|
||||||
collapsed: false
|
collapsed: false
|
||||||
RightRect:
|
RightRect:
|
||||||
|
|
|
@ -348,15 +348,15 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
sensor_msgs::Temperature>(temperature_topic, 100);
|
sensor_msgs::Temperature>(temperature_topic, 100);
|
||||||
NODELET_INFO_STREAM("Advertized on topic " << temperature_topic);
|
NODELET_INFO_STREAM("Advertized on topic " << temperature_topic);
|
||||||
|
|
||||||
// pub_mesh_ = nh_.advertise<visualization_msgs::Marker>("camera_mesh", 0 );
|
pub_mesh_ = nh_.advertise<visualization_msgs::Marker>("camera_mesh", 0 );
|
||||||
// // where to get the mesh from
|
// where to get the mesh from
|
||||||
// std::string mesh_file;
|
std::string mesh_file;
|
||||||
// if (private_nh_.getParam("mesh_file", mesh_file)) {
|
if (private_nh_.getParam("mesh_file", mesh_file)) {
|
||||||
// mesh_msg_.mesh_resource = "package://mynt_eye_ros_wrapper/mesh/"+mesh_file;
|
mesh_msg_.mesh_resource = "package://mynt_eye_ros_wrapper/mesh/"+mesh_file;
|
||||||
// } else {
|
} else {
|
||||||
// LOG(INFO) << "no mesh found for visualisation, set ros param mesh_file, if desired";
|
LOG(INFO) << "no mesh found for visualisation, set ros param mesh_file, if desired";
|
||||||
// mesh_msg_.mesh_resource = "";
|
mesh_msg_.mesh_resource = "";
|
||||||
// }
|
}
|
||||||
|
|
||||||
// stream toggles
|
// stream toggles
|
||||||
|
|
||||||
|
@ -623,8 +623,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
}
|
}
|
||||||
|
|
||||||
void publishTopics() {
|
void publishTopics() {
|
||||||
// publishMesh();
|
publishMesh();
|
||||||
|
|
||||||
if ((camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 ||
|
if ((camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 ||
|
||||||
mono_publishers_[Stream::LEFT].getNumSubscribers() > 0) &&
|
mono_publishers_[Stream::LEFT].getNumSubscribers() > 0) &&
|
||||||
!is_published_[Stream::LEFT]) {
|
!is_published_[Stream::LEFT]) {
|
||||||
|
@ -1169,9 +1168,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
mesh_msg_.pose.orientation.w = 0;
|
mesh_msg_.pose.orientation.w = 0;
|
||||||
|
|
||||||
// fill position
|
// fill position
|
||||||
mesh_msg_.pose.position.x = -0.25;
|
mesh_msg_.pose.position.x = 0;
|
||||||
mesh_msg_.pose.position.y = -0.05;
|
mesh_msg_.pose.position.y = 0;
|
||||||
mesh_msg_.pose.position.z = -0.1;
|
mesh_msg_.pose.position.z = 0;
|
||||||
|
|
||||||
// scale -- needed
|
// scale -- needed
|
||||||
mesh_msg_.scale.x = 0.003;
|
mesh_msg_.scale.x = 0.003;
|
||||||
|
|
Loading…
Reference in New Issue
Block a user