Go to the documentation of this file.    1 #ifndef __TRANSFORMABLE_OBJECT_H__ 
    2 #define __TRANSFORMABLE_OBJECT_H__ 
    5 #include <visualization_msgs/Marker.h> 
    6 #include <visualization_msgs/InteractiveMarker.h> 
    7 #include <visualization_msgs/InteractiveMarkerControl.h> 
    8 #include <std_msgs/Float32.h> 
    9 #include <std_msgs/ColorRGBA.h> 
   12 #include <geometry_msgs/Point.h> 
   13 #include <jsk_rviz_plugins/RequestMarkerOperate.h> 
   16 #include <jsk_interactive_marker/InteractiveSettingConfig.h> 
   23     std::vector<visualization_msgs::InteractiveMarkerControl> 
makeRotateTransFixControl(
unsigned int orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED);
 
   28     void addMarker(visualization_msgs::InteractiveMarker &int_marker, 
bool always_visible = 
true, 
unsigned int interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_3D);
 
   29     void addControl(visualization_msgs::InteractiveMarker &int_marker);
 
   43     void setPose(geometry_msgs::Pose pose, 
bool for_interactive_control=
false);
 
   44     void addPose(geometry_msgs::Pose msg, 
bool relative=
false);
 
   47     geometry_msgs::Pose 
getPose(
bool for_interactive_control=
false);
 
   51     virtual bool setRadius(std_msgs::Float32 recieve_val){
return false;};
 
   53     virtual bool setHeight(std_msgs::Float32 recieve_val){
return false;};
 
   54     virtual bool setX(std_msgs::Float32 recieve_val){
return false;};
 
   55     virtual bool setY(std_msgs::Float32 recieve_val){
return false;};
 
   56     virtual bool setZ(std_msgs::Float32 recieve_val){
return false;};
 
   57     virtual void setRGBA(
float r , 
float g, 
float b, 
float a){};
 
   58     virtual void getRGBA(
float &
r , 
float &g, 
float &b, 
float &a){};
 
   59     virtual void setXYZ(
float x , 
float y, 
float z){};
 
   60     virtual void getXYZ(
float &x, 
float &y, 
float&z){};
 
   61     virtual void setRSR(
float r , 
float sr){};
 
   62     virtual void getRSR(
float &
r , 
float &sr){};
 
   63     virtual void setRZ(
float r , 
float z){};
 
   64     virtual void getRZ(
float &
r , 
float &z){};
 
  114     void getXYZ(
float &x, 
float &y, 
float&z){
return;};
 
  116     bool setY(std_msgs::Float32 y){
return true;};
 
  117     bool setZ(std_msgs::Float32 z){
return true;};
 
  134     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);
 
 
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)