feat(*): add 3dmodel rotation config.

This commit is contained in:
TinyO 2019-09-18 16:35:40 +08:00
parent 4422c447bc
commit ccfee8b6b7
7 changed files with 54 additions and 8 deletions

View File

@ -0,0 +1,10 @@
# this file is used to config mesh file in rviz display
s1030_mesh_file: "S1030-0315.obj"
model_rotation_x: 1.5708
model_rotation_y: 0
model_rotation_z: 1.5708

View File

@ -0,0 +1,10 @@
# this file is used to config mesh file in rviz display
s1030_mesh_file: "S1030-0315.obj"
model_rotation_x: 1.5708
model_rotation_y: 0
model_rotation_z: 1.5708

View File

@ -0,0 +1,10 @@
# this file is used to config mesh file in rviz display
s1030_mesh_file: "S1030-0315.obj"
model_rotation_x: 1.5708
model_rotation_y: 0
model_rotation_z: 1.5708

View File

@ -43,7 +43,6 @@
<arg name="gravity" default="9.8" />
<arg name="mesh_file" default="S1030-0315.obj" />
<!-- Push down all topics/nodelets into "mynteye" namespace -->
<group ns="$(arg mynteye)">
@ -65,7 +64,6 @@
<param name="disparity_norm_topic" value="$(arg disparity_norm_topic)" />
<param name="points_topic" value="$(arg points_topic)" />
<param name="depth_topic" value="$(arg depth_topic)" />
<param name="mesh_file" value="$(arg mesh_file)" />
<param name="left_mono_topic" value="$(arg left_mono_topic)" />
<param name="right_mono_topic" value="$(arg right_mono_topic)" />
@ -88,6 +86,7 @@
<rosparam file="$(find mynt_eye_ros_wrapper)/config/device/standard.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/device/standard2.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/process/process_config.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/mesh/mesh.yaml" command="load" />
<param name="gravity" value="$(arg gravity)" />
</node>

View File

@ -65,7 +65,6 @@
<param name="disparity_norm_topic" value="$(arg disparity_norm_topic)" />
<param name="points_topic" value="$(arg points_topic)" />
<param name="depth_topic" value="$(arg depth_topic)" />
<param name="mesh_file" value="$(arg mesh_file)" />
<param name="left_mono_topic" value="$(arg left_mono_topic)" />
<param name="right_mono_topic" value="$(arg right_mono_topic)" />
@ -88,6 +87,7 @@
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/device_1/standard.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/device_1/standard2.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/process_1/process_config.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/mesh_1/mesh.yaml" command="load" />
<param name="gravity" value="$(arg gravity)" />
</node>

View File

@ -43,7 +43,6 @@
<arg name="gravity" default="9.8" />
<arg name="mesh_file" default="S1030-0315.obj" />
<!-- Push down all topics/nodelets into "mynteye" namespace -->
<group ns="$(arg mynteye)">
@ -65,7 +64,6 @@
<param name="disparity_norm_topic" value="$(arg disparity_norm_topic)" />
<param name="points_topic" value="$(arg points_topic)" />
<param name="depth_topic" value="$(arg depth_topic)" />
<param name="mesh_file" value="$(arg mesh_file)" />
<param name="left_mono_topic" value="$(arg left_mono_topic)" />
<param name="right_mono_topic" value="$(arg right_mono_topic)" />
@ -88,6 +86,7 @@
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/device_2/standard.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/device_2/standard2.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/process_2/process_config.yaml" command="load" />
<rosparam file="$(find mynt_eye_ros_wrapper)/config/sub/mesh_2/mesh.yaml" command="load" />
<param name="gravity" value="$(arg gravity)" />
</node>

View File

@ -43,6 +43,8 @@
#include "configuru.hpp"
using namespace configuru; // NOLINT
#define PIE 3.1416
#define FULL_PRECISION \
std::fixed << std::setprecision(std::numeric_limits<double>::max_digits10)
@ -62,6 +64,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
skip_tmp_left_tag = 0;
skip_tmp_right_tag = 0;
unit_hard_time *= 10;
mesh_rotation_x = PIE/2;
mesh_rotation_y = 0.0;
mesh_rotation_z = PIE/2;
}
~ROSWrapperNodelet() {
@ -196,6 +201,13 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
pthread_mutex_init(&mutex_data_, nullptr);
private_nh_.getParamCached("model_rotation_x",
mesh_rotation_x);
private_nh_.getParamCached("model_rotation_y",
mesh_rotation_y);
private_nh_.getParamCached("model_rotation_z",
mesh_rotation_z);
// node params
std::map<Stream, std::string> stream_names{
@ -404,7 +416,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
pub_mesh_ = nh_.advertise<visualization_msgs::Marker>("camera_mesh", 0 );
// where to get the mesh from
std::string mesh_file;
if (private_nh_.getParamCached("mesh_file", mesh_file)) {
if (private_nh_.getParamCached("s1030_mesh_file", mesh_file)) {
mesh_msg_.mesh_resource = "package://mynt_eye_ros_wrapper/mesh/"+mesh_file;
} else {
LOG(INFO) << "no mesh found for visualisation, set ros param mesh_file, if desired";
@ -1271,8 +1283,11 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
mesh_msg_.header.stamp = ros::Time::now();
mesh_msg_.type = visualization_msgs::Marker::MESH_RESOURCE;
geometry_msgs::Quaternion q;
double Pie = 3.1416;
q = tf::createQuaternionMsgFromRollPitchYaw(Pie/2, 0.0, Pie/2);
q = tf::createQuaternionMsgFromRollPitchYaw(
mesh_rotation_x,
mesh_rotation_y,
mesh_rotation_z);
// fill orientation
mesh_msg_.pose.orientation.x = q.x;
@ -1650,6 +1665,9 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
int skip_tag;
int skip_tmp_left_tag;
int skip_tmp_right_tag;
double mesh_rotation_x;
double mesh_rotation_y;
double mesh_rotation_z;
std::uint64_t unit_hard_time = std::numeric_limits<std::uint32_t>::max();
};