00001 #include <jsk_interactive_marker/transformable_object.h>
00002 #include <eigen_conversions/eigen_msg.h>
00003 #include <math.h>
00004
00005 #define PI 3.14159265
00006
00007 using namespace jsk_interactive_marker;
00008
00009 inline geometry_msgs::Pose inverse(geometry_msgs::Pose pose){
00010 Eigen::Affine3d pose_eigen;
00011 tf::poseMsgToEigen(pose, pose_eigen);
00012 tf::poseEigenToMsg(pose_eigen.inverse(), pose);
00013 return pose;
00014 }
00015
00016
00017 TransformableObject::TransformableObject(){
00018 ROS_INFO("Init TransformableObject");
00019 control_offset_pose_.orientation.x = 0;
00020 control_offset_pose_.orientation.y = 0;
00021 control_offset_pose_.orientation.z = 0;
00022 control_offset_pose_.orientation.w = 1;
00023 pose_ = control_offset_pose_;
00024 display_interactive_manipulator_ = true;
00025 display_description_ = true;
00026 }
00027
00028 void TransformableObject::setDisplayInteractiveManipulator(bool v)
00029 {
00030 display_interactive_manipulator_ = v;
00031 }
00032
00033 void TransformableObject::setDisplayDescription(bool v)
00034 {
00035 display_description_ = v;
00036 }
00037
00038 void TransformableObject::setInteractiveMarkerSetting(const InteractiveSettingConfig& config){
00039 display_interactive_manipulator_ = config.display_interactive_manipulator;
00040 display_description_ = config.display_description_only_selected ? false : true;
00041 interactive_manipulator_orientation_ = config.interactive_manipulator_orientation;
00042 interaction_mode_ = static_cast<unsigned int>(config.interaction_mode);
00043 }
00044
00045 std::vector<visualization_msgs::InteractiveMarkerControl> TransformableObject::makeRotateTransFixControl(unsigned int orientation_mode){
00046 visualization_msgs::InteractiveMarkerControl control;
00047
00048 std::vector<visualization_msgs::InteractiveMarkerControl> controls;
00049 control.orientation_mode = orientation_mode;
00050 control.orientation.w = 1;
00051 control.orientation.x = 1;
00052 control.orientation.y = 0;
00053 control.orientation.z = 0;
00054 control.name = "rotate_x";
00055 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00056 controls.push_back(control);
00057 control.name = "move_x";
00058 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00059 controls.push_back(control);
00060
00061 control.orientation.w = 1;
00062 control.orientation.x = 0;
00063 control.orientation.y = 1;
00064 control.orientation.z = 0;
00065 control.name = "rotate_z";
00066 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00067 controls.push_back(control);
00068 control.name = "move_z";
00069 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00070 controls.push_back(control);
00071
00072 control.orientation.w = 1;
00073 control.orientation.x = 0;
00074 control.orientation.y = 0;
00075 control.orientation.z = 1;
00076 control.name = "rotate_y";
00077 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00078 controls.push_back(control);
00079 control.name = "move_y";
00080 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00081 controls.push_back(control);
00082
00083 return controls;
00084 };
00085
00086 void TransformableObject::addMarker(visualization_msgs::InteractiveMarker &int_marker, bool always_visible, unsigned int interaction_mode)
00087 {
00088 visualization_msgs::Marker marker = getVisualizationMsgMarker();
00089 visualization_msgs::InteractiveMarkerControl marker_control;
00090 marker_control.always_visible = always_visible;
00091 marker_control.markers.push_back(marker);
00092 marker_control.interaction_mode = interaction_mode;
00093 int_marker.controls.push_back(marker_control);
00094 };
00095
00096 void TransformableObject::addControl(visualization_msgs::InteractiveMarker &int_marker)
00097 {
00098 if(display_interactive_manipulator_){
00099 std::vector<visualization_msgs::InteractiveMarkerControl> rotate_controls = makeRotateTransFixControl(interactive_manipulator_orientation_);
00100 int_marker.controls.insert(int_marker.controls.end(), rotate_controls.begin(), rotate_controls.end());
00101 }
00102 };
00103
00104 visualization_msgs::InteractiveMarker TransformableObject::getInteractiveMarker(){
00105 visualization_msgs::InteractiveMarker int_marker;
00106
00107 addMarker(int_marker, true, interaction_mode_);
00108 addControl(int_marker);
00109 int_marker.header.frame_id = frame_id_;
00110 int_marker.name = name_;
00111 if (display_description_) {
00112 int_marker.description = description_;
00113 } else {
00114 int_marker.description = "";
00115 }
00116 int_marker.pose = pose_;
00117 int_marker.scale = getInteractiveMarkerScale();
00118 return int_marker;
00119 };
00120
00121 void TransformableObject::setPose(geometry_msgs::Pose pose, bool for_interactive_control){
00122 if(for_interactive_control) {
00123 pose_ = pose;
00124 }
00125 else {
00126 Eigen::Affine3d control_offset_eigen;
00127 tf::poseMsgToEigen(control_offset_pose_, control_offset_eigen);
00128 Eigen::Affine3d pose_eigen;
00129 tf::poseMsgToEigen(pose, pose_eigen);
00130 tf::poseEigenToMsg(pose_eigen * control_offset_eigen, pose_);
00131 }
00132 }
00133
00134 geometry_msgs::Pose TransformableObject::getPose(bool for_interactive_control){
00135 if(for_interactive_control) {
00136 return pose_;
00137 }
00138 else{
00139 geometry_msgs::Pose pose;
00140 Eigen::Affine3d control_offset_eigen;
00141 tf::poseMsgToEigen(control_offset_pose_, control_offset_eigen);
00142 Eigen::Affine3d pose_eigen;
00143 tf::poseMsgToEigen(pose_, pose_eigen);
00144 tf::poseEigenToMsg(pose_eigen * control_offset_eigen.inverse(), pose);
00145
00146 return pose;
00147 }
00148 }
00149
00150
00151 void TransformableObject::addPose(geometry_msgs::Pose msg, bool relative){
00152 Eigen::Vector3d original_p(msg.position.x, msg.position.y, msg.position.z);
00153 Eigen::Quaterniond original_q;
00154 tf::quaternionMsgToEigen(pose_.orientation, original_q);
00155 Eigen::Quaterniond diff_q;
00156 tf::quaternionMsgToEigen(msg.orientation, diff_q);
00157 Eigen::Quaterniond updated_q;
00158 if(relative) {
00159 original_p = Eigen::Affine3d(original_q) * original_p;
00160 }
00161 if(relative) {
00162 updated_q = original_q * diff_q;
00163 } else {
00164 updated_q = diff_q * original_q;
00165 }
00166 pose_.position.x += original_p[0];
00167 pose_.position.y += original_p[1];
00168 pose_.position.z += original_p[2];
00169 tf::quaternionEigenToMsg(updated_q, pose_.orientation);
00170 }
00171
00172 void TransformableObject::publishTF(){
00173 tf::Transform transform;
00174 tf::poseMsgToTF(getPose(), transform);
00175 br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), frame_id_, name_));
00176 }
00177
00178 namespace jsk_interactive_marker{
00179 TransformableCylinder::TransformableCylinder( float radius, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description){
00180 cylinder_radius_ = radius;
00181 cylinder_z_ = z;
00182 cylinder_r_ = r;
00183 cylinder_g_ = g;
00184 cylinder_b_ = b;
00185 cylinder_a_ = a;
00186 marker_.type = visualization_msgs::Marker::CYLINDER;
00187 type_ = jsk_rviz_plugins::TransformableMarkerOperate::CYLINDER;
00188
00189 frame_id_ = frame;
00190 name_ = name;
00191 description_ = description;
00192 }
00193
00194 visualization_msgs::Marker TransformableCylinder::getVisualizationMsgMarker(){
00195 marker_.scale.x = cylinder_radius_ * 2.0;
00196 marker_.scale.y = cylinder_radius_ * 2.0;
00197 marker_.scale.z = cylinder_z_;
00198 marker_.color.r = cylinder_r_;
00199 marker_.color.g = cylinder_g_;
00200 marker_.color.b = cylinder_b_;
00201 marker_.color.a = cylinder_a_;
00202 marker_.pose = control_offset_pose_;
00203 return marker_;
00204 }
00205 }
00206
00207 namespace jsk_interactive_marker{
00208
00209 TransformableTorus::TransformableTorus( float radius, float small_radius, int u_div, int v_div, float r, float g, float b, float a, std::string frame, std::string name, std::string description){
00210 torus_radius_ = radius;
00211 torus_small_radius_ = small_radius;
00212 torus_r_ = r;
00213 torus_g_ = g;
00214 torus_b_ = b;
00215 torus_a_ = a;
00216 marker_.type = visualization_msgs::Marker::TRIANGLE_LIST;
00217 type_ = jsk_rviz_plugins::TransformableMarkerOperate::TORUS;
00218
00219 frame_id_ = frame;
00220 name_ = name;
00221 description_ = description;
00222
00223 u_division_num_ = u_div;
00224 v_division_num_ = v_div;
00225 }
00226
00227 std::vector<geometry_msgs::Point > TransformableTorus::calcurateTriangleMesh(){
00228 std::vector<geometry_msgs::Point> triangle_mesh;
00229 float center_x = 0;
00230 float center_y = 0;
00231 float u_division_num = u_division_num_;
00232 float v_division_num = v_division_num_;
00233 std::vector<std::vector<geometry_msgs::Point> > points_array;
00234 for (int i = 0; i < u_division_num; i ++){
00235 std::vector<geometry_msgs::Point> points;
00236 float target_circle_x = torus_radius_ * cos( ( i / u_division_num) * 2 * PI) ;
00237 float target_circle_y = torus_radius_ * sin( ( i / u_division_num) * 2 * PI) ;
00238 for (int j = 0; j < v_division_num; j++){
00239 geometry_msgs::Point new_point;
00240 new_point.x = target_circle_x + torus_small_radius_ * cos ( (j / v_division_num) * 2 * PI) * cos( ( i / u_division_num) * 2 * PI);
00241 new_point.y = target_circle_y + torus_small_radius_ * cos ( (j / v_division_num) * 2 * PI) * sin( ( i / u_division_num) * 2 * PI);
00242 new_point.z = torus_small_radius_ * sin ( (j / v_division_num) * 2 * PI);
00243 points.push_back(new_point);
00244 }
00245 points_array.push_back(points);
00246 }
00247
00248
00249 for(int i = 0; i < u_division_num; i++){
00250 std::vector<geometry_msgs::Point> target_points = points_array[i];
00251 float prev_index = i - 1, next_index = i + 1;
00252 if(prev_index < 0)
00253 prev_index = u_division_num - 1;
00254 if(next_index > u_division_num - 1)
00255 next_index = 0;
00256 std::vector<geometry_msgs::Point> prev_points = points_array[prev_index];
00257 std::vector<geometry_msgs::Point> next_points = points_array[next_index];
00258 for(int j = 0; j < v_division_num; j++){
00259 float next_point_index = j + 1;
00260 if( next_point_index > v_division_num - 1)
00261 next_point_index = 0;
00262
00263 triangle_mesh.push_back(target_points[j]);
00264 triangle_mesh.push_back(next_points[j]);
00265 triangle_mesh.push_back(target_points[next_point_index]);
00266
00267 triangle_mesh.push_back(target_points[j]);
00268 triangle_mesh.push_back(target_points[next_point_index]);
00269 triangle_mesh.push_back(prev_points[next_point_index]);
00270 }
00271 }
00272
00273 return triangle_mesh;
00274 }
00275
00276 visualization_msgs::Marker TransformableTorus::getVisualizationMsgMarker(){
00277 marker_.points = calcurateTriangleMesh();
00278 marker_.color.r = torus_r_;
00279 marker_.color.g = torus_g_;
00280 marker_.color.b = torus_b_;
00281 marker_.color.a = torus_a_;
00282 return marker_;
00283 }
00284 }
00285
00286 namespace jsk_interactive_marker{
00287
00288 TransformableBox::TransformableBox( float length , float r, float g, float b, float a, std::string frame, std::string name, std::string description){
00289 box_x_ = box_y_ = box_z_ = length;
00290
00291 box_r_ = r;
00292 box_g_ = g;
00293 box_b_ = b;
00294 box_a_ = a;
00295 marker_.type = visualization_msgs::Marker::CUBE;
00296
00297 frame_id_ = frame;
00298 name_ = name;
00299 description_ = description;
00300 }
00301
00302 TransformableBox::TransformableBox( float x, float y, float z , float r, float g, float b, float a, std::string frame, std::string name, std::string description){
00303 box_x_ = x;
00304 box_y_ = y;
00305 box_z_ = z;
00306 box_r_ = r;
00307 box_g_ = g;
00308 box_b_ = b;
00309 box_a_ = a;
00310 marker_.type = visualization_msgs::Marker::CUBE;
00311 type_ = jsk_rviz_plugins::TransformableMarkerOperate::BOX;
00312
00313 frame_id_ = frame;
00314 name_ = name;
00315 description_ = description;
00316 }
00317
00318 visualization_msgs::Marker TransformableBox::getVisualizationMsgMarker(){
00319 marker_.scale.x = box_x_;
00320 marker_.scale.y = box_y_;
00321 marker_.scale.z = box_z_;
00322 marker_.color.r = box_r_;
00323 marker_.color.g = box_g_;
00324 marker_.color.b = box_b_;
00325 marker_.color.a = box_a_;
00326 return marker_;
00327 }
00328 }
00329
00330 namespace jsk_interactive_marker{
00331
00332 TransformableMesh::TransformableMesh( std::string frame, std::string name, std::string description, std::string mesh_resource, bool mesh_use_embedded_materials){
00333 marker_scale_ = 0.5;
00334 marker_.type = visualization_msgs::Marker::MESH_RESOURCE;
00335 type_ = jsk_rviz_plugins::TransformableMarkerOperate::MESH_RESOURCE;
00336 mesh_resource_ = mesh_resource;
00337 mesh_use_embedded_materials_ = mesh_use_embedded_materials;
00338 frame_id_ = frame;
00339 name_ = name;
00340 description_ = description;
00341 }
00342
00343 visualization_msgs::Marker TransformableMesh::getVisualizationMsgMarker(){
00344 marker_.mesh_resource = mesh_resource_;
00345 marker_.mesh_use_embedded_materials = mesh_use_embedded_materials_;
00346 marker_.scale.x = 1.0;
00347 marker_.scale.y = 1.0;
00348 marker_.scale.z = 1.0;
00349 marker_.color.r = mesh_r_;
00350 marker_.color.g = mesh_g_;
00351 marker_.color.b = mesh_b_;
00352 marker_.color.a = mesh_a_;
00353 marker_.pose = inverse(control_offset_pose_);
00354 return marker_;
00355 }
00356 }