item corresponds to a robot model More...
Classes | |
class | MenuChangeType |
class | NormalRender |
Public Member Functions | |
void | addLink (GrxLinkItem link) |
add a link More... | |
void | addRobot (File f, GrxLinkItem parentLink) |
load and add a new robot as a child More... | |
void | calcForwardKinematics () |
compute forward kinematics More... | |
void | cancelModified () |
int | checkModifiedModel (boolean reload) |
GrxModelItem | clone () |
Override clone method. More... | |
boolean | create () |
create a new model More... | |
void | delete () |
BodyInfo | getBodyInfo () |
get BodyInfo More... | |
List< Camera_impl > | getCameraSequence () |
get sequence of cameras More... | |
void | getCoM (Vector3d pos) |
compute center of mass More... | |
int | getDOF () |
double [] | getInitialJointMode () |
double [] | getInitialJointValues () |
double [] | getInitialJointVelocity () |
double [] | getInitialTransformArray (GrxLinkItem link) |
double [] | getInitialVelocity (GrxLinkItem link) |
String [] | getJointNames () |
double [] | getJointValues () |
GrxLinkItem | getLink (String name) |
get link from name More... | |
List< GrxModelItem > | getSameUrlModels () |
String [] | getSensorNames (String type) |
List< GrxSensorItem > | getSensors (String type) |
double [] | getTransformArray (GrxLinkItem link) |
get transform of link in array form More... | |
TransformGroup | getTransformGroupRoot () |
ValueEditType | GetValueEditType (String key) |
GrxModelItem (String name, GrxPluginManager item) | |
constructor More... | |
boolean | isModified () |
boolean | isRobot () |
boolean | load (File f) |
load a model from file More... | |
void | makeAABBforSameUrlModels () |
void | notifyModified () |
notify this model is modified More... | |
boolean | propertyChanged (String property, String value) |
check validity of new value of property and update if valid More... | |
boolean | registerCharacter (BodyInfo bInfo) |
boolean | reload () |
void | removeExtraJoint (GrxExtraJointItem extraJoint) |
void | removeLink (GrxLinkItem link) |
remove a link More... | |
void | rename (String newName) |
rename this Model More... | |
void | resizeBoundingBox () |
resize bounding box which covers the whole body More... | |
void | restoreProperties () |
restore properties More... | |
GrxLinkItem | rootLink () |
get root link More... | |
boolean | saveAndLoad () |
void | setCharacterPos (LinkPosition[] lpos, double[] q) |
set transformation of the root joint and all joint values More... | |
void | setFocused (boolean b) |
set/unset focus on this item More... | |
void | setJointColor (int jid, java.awt.Color color) |
set color of joint More... | |
void | setJointValues (final double[] values) |
set joint values More... | |
void | setJointValuesWithinLimit () |
modify joint value if it exceeds limit values More... | |
void | setSelected (boolean b) |
void | setTransformRoot (Vector3d pos, Matrix3d rot) |
set transformation of the root joint More... | |
void | setTransformRoot (Transform3D tform) |
set transformation of the root joint More... | |
void | setTransparencyMode (boolean b) |
void | setVisibleAABB (boolean b) |
void | setVisibleCoM (boolean b) |
set visibility of CoM More... | |
void | setVisibleCoMonFloor (boolean b) |
set visibility of CoM projected on the floor More... | |
void | setWireFrame (boolean b) |
switch display mode between fill and line More... | |
void | setWireFrame (boolean b, Node node) |
switch display mode between fill and line More... | |
void | updateCoM () |
update CoM and projected CoM positions More... | |
void | updateInitialJointValue (GrxLinkItem link) |
update joint value property from current joint value More... | |
void | updateInitialJointValues () |
void | updateInitialTransformRoot () |
update initial transformation property from current Transform3D More... | |
Public Member Functions inherited from com.generalrobotix.ui.GrxBaseItem | |
File | chooseSaveFile () |
GrxBaseItem | clone () |
Override clone method. More... | |
boolean | create () |
void | delete () |
delete this item More... | |
File | getDefaultDir () |
get default directory More... | |
String | getFileExtention () |
get file extension More... | |
Object | getValue () |
boolean | load (File file) |
void | paste (String clipVal) |
paste object More... | |
void | setValue (Object o) |
Public Member Functions inherited from com.generalrobotix.ui.GrxBasePlugin | |
void | addObserver (GrxObserver v) |
GrxBasePlugin | clone () |
Override clone method. More... | |
void | deleteObserver (GrxObserver v) |
boolean | equals (Object obj) |
check whether obj equals to this More... | |
Element | getElement () |
get element More... | |
Image | getIcon () |
get icon More... | |
Vector< Action > | getMenu () |
get menu More... | |
String [] | getMenuPath () |
get menu path More... | |
final String | getName () |
get name More... | |
ArrayList< GrxObserver > | getObserver () |
String | getOldName () |
Vector< MenuManager > | getSubMenu () |
get subMenu More... | |
String | getURL (boolean expand) |
ValueEditType | GetValueEditType (String key) |
Return editing type of the key item. More... | |
boolean | isExclusive () |
check whether this is exclusive or not More... | |
boolean | isSelected () |
check whether this is selected or not More... | |
void | notifyObservers (Object... arg) |
boolean | propertyChanged (String property, String value) |
check validity of new value of property and update if valid More... | |
boolean | registerCORBA () |
void | rename (String newName) |
rename this item More... | |
void | restoreProperties () |
restore properties. Called by menu item "restore Properties" More... | |
void | setDocument (Document doc) |
set document More... | |
void | setElement (Element element) |
set element More... | |
void | setExclusive (boolean b) |
set exclusive flag More... | |
void | setFocused (boolean b) |
set/unset focus on this plugin More... | |
void | setMenuItem (Action a) |
add a menu item More... | |
void | setName (String name) |
set name More... | |
Object | setProperty (String key, String value) |
set property value associated with a keyword More... | |
void | setSelected (boolean b) |
set selected flag More... | |
void | setSubMenu (MenuManager m) |
add a submenu More... | |
void | setURL (String url) |
set URL property More... | |
void | shutdown () |
Element | storeProperties () |
store properties More... | |
final String | toString () |
convert to String. Currently, name is returned. More... | |
void | unregisterCORBA () |
Public Member Functions inherited from com.generalrobotix.ui.util.GrxConfigBundle | |
final Double | getDbl (String key, Double defaultVal) |
get double value associated to key More... | |
Double | getDbl (String value) |
final double [] | getDblAry (String key, double[] defaultVal) |
get double array associated to key More... | |
double [] | getDblAry (String value) |
get array of double from String More... | |
final Float | getFlt (String key, Float defaultVal) |
get float value associated to key More... | |
final Float | getFlt (String value) |
final float [] | getFltAry (String key, float[] defaultVal) |
get float array associated to key More... | |
float [] | getFltAry (String value) |
final Integer | getInt (String key, Integer defaultVal) |
get integer value associated to key More... | |
final int [] | getIntAry (String key) |
get integer array associated to key More... | |
final Short | getShort (String key, Short defaultVal) |
get short value associated to key More... | |
Short | getShort (String value) |
final String | getStr (String key) |
get value associated to keyword More... | |
final String | getStr (String key, String defaultVal) |
get value associated to key More... | |
GrxConfigBundle () | |
constructor More... | |
GrxConfigBundle (String fname) throws IOException | |
construct from a file More... | |
final boolean | isFalse (String key) |
check whether value associated to key includes a word "false" More... | |
final boolean | isFalse (String key, boolean defaultVal) |
check whether value associated to key includes a word "false" More... | |
final boolean | isTrue (String key) |
check whether value associated to key includes a word "true" More... | |
final boolean | isTrue (String key, boolean defaultVal) |
check whether value associated to key includes a word "true" More... | |
void | load (String fname) throws IOException |
load config from a file More... | |
final void | setBool (String key, boolean value) |
final void | setDbl (String key, double value) |
associate double value to key More... | |
final void | setDbl (String key, double value, int digits) |
associate double value to key More... | |
final void | setDblAry (String key, double[] value, int digits) |
associate double array to key More... | |
final void | setDblAry (String key, double[] value) |
associate double array to key More... | |
final void | setFlt (String key, float value) |
associate float value to key More... | |
final void | setFltAry (String key, float[] value) |
associate float array to key More... | |
final void | setInt (String key, int value) |
associate int value to key More... | |
final void | setShort (String key, short value) |
associate short value to key More... | |
void | store (String fname, String comments) throws IOException |
store this config More... | |
Public Attributes | |
AppearanceInfo [] | appearances = null |
BranchGroup | bgRoot_ = new BranchGroup() |
Vector< GrxExtraJointItem > | extraJoints_ = new Vector<GrxExtraJointItem>() |
Vector< GrxLinkItem > | links_ = new Vector<GrxLinkItem>() |
MaterialInfo [] | materials = null |
Map< String, GrxLinkItem > | nameToLink_ = new HashMap<String, GrxLinkItem>() |
ShapeInfo [] | shapes = null |
TextureInfo [] | textures = null |
Static Public Attributes | |
static final String | DEFAULT_DIR = "/../model" |
static final String | FILE_EXTENSION = "*" |
static final int | MODIFIED_NG =1 |
static final int | MODIFIED_NOT =2 |
static final int | MODIFIED_OK =0 |
static final String | TITLE = "Model" |
Private Member Functions | |
void | _globalToRoot (Vector3d pos) |
convert global position into robot local More... | |
void | _initMenu () |
initialize right-click menu More... | |
void | _loadVrmlScene (LinkInfo[] links) throws BadLinkStructureException |
create shapes of links More... | |
boolean | _saveAs () |
save this model as a VRML file More... | |
void | _setModelType (String value) |
set model type(robot or environment) from String More... | |
void | _setModelType (boolean isRobot) |
set model type(robot or environment) More... | |
void | _setTransform (int linkId, Vector3d pos, Matrix3d rot) |
set transformation of linkId th joint More... | |
void | _setupMarks () |
create spheres to display CoM and projected CoM More... | |
void | addExtraJoint (String name) |
void | createLink (int index) |
make connections between links and gather cameras More... | |
BodyInfo | getBodyInfoFromModelLoader () |
boolean | load0 (File f) |
void | makeAABB (BodyInfo binfo) |
boolean | registerCharacter () |
void | sameUrlModelLoad () |
void | setTransparencyMode (boolean b, Node node) |
Private Attributes | |
BodyInfo | bInfo_ |
boolean | bModified_ = false |
List< Camera_impl > | cameraList_ = new ArrayList<Camera_impl>() |
boolean | isRobot_ = true |
int [] | jointToLink_ |
Switch | switchBb_ |
Switch | switchCom_ |
Switch | switchComZ0_ |
TransformGroup | tgCom_ |
TransformGroup | tgComZ0_ |
Static Private Attributes | |
static final double | DEFAULT_RADIUS = 0.05 |
static final String | envIcon = "environment.png" |
static final String | robotIcon = "robot.png" |
Additional Inherited Members | |
Static Public Member Functions inherited from com.generalrobotix.ui.GrxBasePlugin | |
static Object | getField (Class<? extends GrxBasePlugin > cls, String field, Object defaultValue) |
get field More... | |
Protected Member Functions inherited from com.generalrobotix.ui.GrxBaseItem | |
GrxBaseItem (String name, GrxPluginManager manager) | |
constructor More... | |
void | setDefaultDirectory (String dir) |
void | setFileExtension (String ext) |
Protected Member Functions inherited from com.generalrobotix.ui.GrxBasePlugin | |
GrxBasePlugin (String name, GrxPluginManager manager) | |
constructor More... | |
void | setIcon (String iconName) |
set icon More... | |
void | setMenuPath (String[] path) |
set menu path More... | |
boolean | syncExec (Runnable r) |
Transfer SWT UI thread. More... | |
Protected Attributes inherited from com.generalrobotix.ui.GrxBaseItem | |
String | clipValue_ = "" |
File | file_ |
Protected Attributes inherited from com.generalrobotix.ui.GrxBasePlugin | |
Document | doc_ |
Element | element_ |
GrxPluginManager | manager_ |
Static Protected Attributes inherited from com.generalrobotix.ui.GrxBaseItem | |
static final String [] | jointTypeComboItem_ = new String[] { "fixed", "rotate", "free", "slide" } |
static final String [] | methodComboItem_ = new String[] { "EULER", "RUNGE_KUTTA" } |
static final String [] | modeComboItem_ = new String[] { "Torque", "HighGain" } |
Static Protected Attributes inherited from com.generalrobotix.ui.GrxBasePlugin | |
static final String [] | booleanComboItem_ = new String[] {"true", "false" } |
static final String | INDENT4 = " " |
static final String | ITEM_TAG = "item" |
static final String | PROPERTY_TAG = "property" |
static final String | VIEW_TAG = "view" |
item corresponds to a robot model
Definition at line 52 of file GrxModelItem.java.
|
inline |
constructor
name | name of this item |
item | plugin manager |
Definition at line 219 of file GrxModelItem.java.
|
inlineprivate |
convert global position into robot local
pos | global position It is overwritten by robot local position |
Definition at line 1086 of file GrxModelItem.java.
|
inlineprivate |
initialize right-click menu
Definition at line 265 of file GrxModelItem.java.
|
inlineprivate |
create shapes of links
links | array of LinkInfo retrieved from ModelLoader |
BadLinkStructureException |
Definition at line 771 of file GrxModelItem.java.
|
inlineprivate |
save this model as a VRML file
Definition at line 350 of file GrxModelItem.java.
|
inlineprivate |
set model type(robot or environment) from String
value | "true" or "false" |
Definition at line 504 of file GrxModelItem.java.
set model type(robot or environment)
isRobot | true if this model is robot, false otherwise |
Definition at line 515 of file GrxModelItem.java.
|
inlineprivate |
set transformation of linkId th joint
linkId | id of the link |
pos | position |
rot | rotation matrix |
Definition at line 990 of file GrxModelItem.java.
|
inlineprivate |
create spheres to display CoM and projected CoM
Definition at line 536 of file GrxModelItem.java.
|
inlineprivate |
Definition at line 1673 of file GrxModelItem.java.
|
inline |
add a link
This method is called by constructor of GrxLinkItem
link | link to be added |
Definition at line 246 of file GrxModelItem.java.
|
inline |
load and add a new robot as a child
f | file name of the new robot |
Definition at line 810 of file GrxModelItem.java.
|
inline |
compute forward kinematics
Definition at line 1055 of file GrxModelItem.java.
|
inline |
Definition at line 157 of file GrxModelItem.java.
Definition at line 109 of file GrxModelItem.java.
|
inline |
|
inline |
create a new model
Definition at line 368 of file GrxModelItem.java.
make connections between links and gather cameras
index | index of link in links_ |
Definition at line 737 of file GrxModelItem.java.
|
inline |
delete this item
Definition at line 1283 of file GrxModelItem.java.
|
inline |
|
inlineprivate |
Definition at line 1550 of file GrxModelItem.java.
|
inline |
get sequence of cameras
Definition at line 1466 of file GrxModelItem.java.
|
inline |
compute center of mass
pos | computed center of mass |
Definition at line 1100 of file GrxModelItem.java.
|
inline |
Definition at line 1196 of file GrxModelItem.java.
|
inline |
Definition at line 1244 of file GrxModelItem.java.
|
inline |
Definition at line 1216 of file GrxModelItem.java.
|
inline |
Definition at line 1226 of file GrxModelItem.java.
|
inline |
Definition at line 1162 of file GrxModelItem.java.
|
inline |
Definition at line 1182 of file GrxModelItem.java.
|
inline |
Definition at line 1202 of file GrxModelItem.java.
|
inline |
Definition at line 1209 of file GrxModelItem.java.
|
inline |
get link from name
name | name of the link |
Definition at line 1546 of file GrxModelItem.java.
|
inline |
Definition at line 1591 of file GrxModelItem.java.
|
inline |
Definition at line 1126 of file GrxModelItem.java.
|
inline |
Definition at line 1116 of file GrxModelItem.java.
|
inline |
get transform of link in array form
link | link |
Definition at line 1146 of file GrxModelItem.java.
|
inline |
TransformGroupの参照取得
Implements com.generalrobotix.ui.view.tdview.Manipulatable.
Definition at line 1137 of file GrxModelItem.java.
|
inline |
Definition at line 1658 of file GrxModelItem.java.
|
inline |
Definition at line 102 of file GrxModelItem.java.
|
inline |
Definition at line 1254 of file GrxModelItem.java.
|
inline |
load a model from file
f | file that describes a model |
Definition at line 561 of file GrxModelItem.java.
|
inlineprivate |
Definition at line 586 of file GrxModelItem.java.
|
inlineprivate |
Definition at line 1571 of file GrxModelItem.java.
|
inline |
Definition at line 1602 of file GrxModelItem.java.
|
inline |
notify this model is modified
Definition at line 96 of file GrxModelItem.java.
|
inline |
check validity of new value of property and update if valid
property | name of property |
value | value of property |
Definition at line 442 of file GrxModelItem.java.
|
inline |
Definition at line 624 of file GrxModelItem.java.
|
inlineprivate |
Definition at line 629 of file GrxModelItem.java.
|
inline |
Definition at line 169 of file GrxModelItem.java.
|
inline |
Definition at line 1668 of file GrxModelItem.java.
|
inline |
|
inline |
|
inline |
resize bounding box which covers the whole body
Definition at line 1319 of file GrxModelItem.java.
|
inline |
restore properties
Definition at line 386 of file GrxModelItem.java.
|
inline |
get root link
Definition at line 375 of file GrxModelItem.java.
|
inlineprivate |
Definition at line 176 of file GrxModelItem.java.
|
inline |
Definition at line 162 of file GrxModelItem.java.
|
inline |
set transformation of the root joint and all joint values
lpos | transformation of the root joint |
q | sequence of joint values |
Definition at line 940 of file GrxModelItem.java.
set/unset focus on this item
When this item is focused, its bounding box is displayed.
true | to focus, false to unfocus |
Definition at line 1275 of file GrxModelItem.java.
set color of joint
jid | joint id |
color | color |
Definition at line 1475 of file GrxModelItem.java.
|
inline |
|
inline |
modify joint value if it exceeds limit values
Definition at line 1012 of file GrxModelItem.java.
Definition at line 1258 of file GrxModelItem.java.
|
inline |
set transformation of the root joint
pos | position |
rot | rotation matrix |
Definition at line 968 of file GrxModelItem.java.
|
inline |
set transformation of the root joint
pos | position |
rot | rotation matrix |
Definition at line 977 of file GrxModelItem.java.
b |
Definition at line 1421 of file GrxModelItem.java.
|
inlineprivate |
b | |
node |
Definition at line 1430 of file GrxModelItem.java.
Definition at line 1411 of file GrxModelItem.java.
set visibility of CoM
b | true to make it visible, false otherwise |
Definition at line 1346 of file GrxModelItem.java.
set visibility of CoM projected on the floor
b | true to make it visible, false otherwise |
Definition at line 1359 of file GrxModelItem.java.
switch display mode between fill and line
b | true to switch to line mode, false otherwise |
Definition at line 1372 of file GrxModelItem.java.
switch display mode between fill and line
b | true to switch to line mode, false otherwise |
node | top of subtree to be processed |
Definition at line 1381 of file GrxModelItem.java.
|
inline |
update CoM and projected CoM positions
Definition at line 1063 of file GrxModelItem.java.
|
inline |
update joint value property from current joint value
link | link |
Definition at line 1037 of file GrxModelItem.java.
|
inline |
update initial joint value properties from current joint values
Definition at line 1045 of file GrxModelItem.java.
|
inline |
update initial transformation property from current Transform3D
Definition at line 1019 of file GrxModelItem.java.
AppearanceInfo [] com.generalrobotix.ui.item.GrxModelItem.appearances = null |
Definition at line 78 of file GrxModelItem.java.
BranchGroup com.generalrobotix.ui.item.GrxModelItem.bgRoot_ = new BranchGroup() |
Definition at line 67 of file GrxModelItem.java.
|
private |
Definition at line 64 of file GrxModelItem.java.
|
private |
Definition at line 65 of file GrxModelItem.java.
|
private |
Definition at line 75 of file GrxModelItem.java.
|
static |
Definition at line 54 of file GrxModelItem.java.
|
staticprivate |
Definition at line 56 of file GrxModelItem.java.
|
staticprivate |
Definition at line 60 of file GrxModelItem.java.
Vector<GrxExtraJointItem> com.generalrobotix.ui.item.GrxModelItem.extraJoints_ = new Vector<GrxExtraJointItem>() |
Definition at line 69 of file GrxModelItem.java.
|
static |
Definition at line 55 of file GrxModelItem.java.
|
private |
Definition at line 62 of file GrxModelItem.java.
|
private |
Definition at line 71 of file GrxModelItem.java.
Vector<GrxLinkItem> com.generalrobotix.ui.item.GrxModelItem.links_ = new Vector<GrxLinkItem>() |
Definition at line 68 of file GrxModelItem.java.
MaterialInfo [] com.generalrobotix.ui.item.GrxModelItem.materials = null |
Definition at line 79 of file GrxModelItem.java.
|
static |
Definition at line 107 of file GrxModelItem.java.
|
static |
Definition at line 108 of file GrxModelItem.java.
|
static |
Definition at line 106 of file GrxModelItem.java.
Map<String, GrxLinkItem> com.generalrobotix.ui.item.GrxModelItem.nameToLink_ = new HashMap<String, GrxLinkItem>() |
Definition at line 72 of file GrxModelItem.java.
|
staticprivate |
Definition at line 59 of file GrxModelItem.java.
ShapeInfo [] com.generalrobotix.ui.item.GrxModelItem.shapes = null |
Definition at line 77 of file GrxModelItem.java.
|
private |
Definition at line 91 of file GrxModelItem.java.
|
private |
Definition at line 83 of file GrxModelItem.java.
|
private |
Definition at line 87 of file GrxModelItem.java.
TextureInfo [] com.generalrobotix.ui.item.GrxModelItem.textures = null |
Definition at line 80 of file GrxModelItem.java.
|
private |
Definition at line 84 of file GrxModelItem.java.
|
private |
Definition at line 88 of file GrxModelItem.java.
|
static |
Definition at line 53 of file GrxModelItem.java.