Package yarp

Class ITorqueControl


  • public class ITorqueControl
    extends java.lang.Object
    • Field Detail

      • swigCMemOwn

        protected transient boolean swigCMemOwn
    • Constructor Detail

      • ITorqueControl

        protected ITorqueControl​(long cPtr,
                                 boolean cMemoryOwn)
    • Method Detail

      • finalize

        protected void finalize()
        Overrides:
        finalize in class java.lang.Object
      • delete

        public void delete()
      • setTorqueMode

        public boolean setTorqueMode()
      • setRefTorque

        public boolean setRefTorque​(int j,
                                    double t)
      • setBemfParam

        public boolean setBemfParam​(int j,
                                    double bemf)
      • setTorquePid

        public boolean setTorquePid​(int j,
                                    Pid pid)
      • setTorquePids

        public boolean setTorquePids​(Pid pids)
      • setTorqueErrorLimit

        public boolean setTorqueErrorLimit​(int j,
                                           double limit)
      • setTorqueErrorLimits

        public boolean setTorqueErrorLimits​(SWIGTYPE_p_double limits)
      • getTorquePidOutput

        public boolean getTorquePidOutput​(int j,
                                          SWIGTYPE_p_double out)
      • getTorquePidOutputs

        public boolean getTorquePidOutputs​(SWIGTYPE_p_double outs)
      • getTorquePid

        public boolean getTorquePid​(int j,
                                    Pid pid)
      • getTorquePids

        public boolean getTorquePids​(Pid pids)
      • getTorqueErrorLimit

        public boolean getTorqueErrorLimit​(int j,
                                           SWIGTYPE_p_double limit)
      • getTorqueErrorLimits

        public boolean getTorqueErrorLimits​(SWIGTYPE_p_double limits)
      • resetTorquePid

        public boolean resetTorquePid​(int j)
      • disableTorquePid

        public boolean disableTorquePid​(int j)
      • enableTorquePid

        public boolean enableTorquePid​(int j)
      • setTorqueOffset

        public boolean setTorqueOffset​(int j,
                                       double v)