Package org.robwork.sdurw_models
Class SerialDevice
- java.lang.Object
-
- org.robwork.sdurw_kinematics.Stateless
-
- org.robwork.sdurw_models.Device
-
- org.robwork.sdurw_models.JointDevice
-
- org.robwork.sdurw_models.SerialDevice
-
public class SerialDevice extends JointDevice
The device for a serial chain.
SerialChain is like JointDevice except that SerialChain has the
additional guarantee that the joints lie on a single parent to child
path of the kinematic tree.
-
-
Constructor Summary
Constructors Constructor Description SerialDevice(long cPtr, boolean cMemoryOwn)
SerialDevice(FramePtr first, FramePtr last, java.lang.String name, State state)
Constructor
SerialDevice(FrameVector serialChain, java.lang.String name, State state)
Creates object
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
delete()
FrameVector
frames()
Frames of the device.
This method is being used when displaying the kinematic
structure of devices in RobWorkStudio.static long
getCPtr(SerialDevice obj)
-
Methods inherited from class org.robwork.sdurw_models.JointDevice
baseJCframes, baseJend, getAccelerationLimits, getBase, getBounds, getCPtr, getDOF, getEnd, getJoints, getQ, getVelocityLimits, setAccelerationLimits, setBounds, setQ, setVelocityLimits
-
Methods inherited from class org.robwork.sdurw_models.Device
baseJCend, baseJCframe, baseJframe, baseJframes, baseTend, baseTframe, getCPtr, getName, getPropertyMap, setName, toString, worldTbase
-
Methods inherited from class org.robwork.sdurw_kinematics.Stateless
getCPtr, getStateStructure, isRegistered, registerIn, registerIn, unregister
-
-
-
-
Constructor Detail
-
SerialDevice
public SerialDevice(long cPtr, boolean cMemoryOwn)
-
SerialDevice
public SerialDevice(FramePtr first, FramePtr last, java.lang.String name, State state)
Constructor
- Parameters:
first
- [in] the base frame of the robotlast
- [in] the end-effector of the robotname
- [in] name of devicestate
- [in] the connectedness of the frames
-
SerialDevice
public SerialDevice(FrameVector serialChain, java.lang.String name, State state)
Creates object
- Parameters:
serialChain
- [in] a vector of connected frames. The
first frame in serialChain is the base of the device and
the last frame of serialChain is the end of the device.
The joints of the device are the active joints of
serialChain.
name
- [in] name of device
state
- [in] the initial state of everything
-
-
Method Detail
-
getCPtr
public static long getCPtr(SerialDevice obj)
-
delete
public void delete()
- Overrides:
delete
in classJointDevice
-
frames
public FrameVector frames()
Frames of the device.
This method is being used when displaying the kinematic
structure of devices in RobWorkStudio. The method really
isn't of much use for everyday programming.
- Returns:
- list of raw Frame pointers.
-
-