23 #ifndef EV3_JOINT_SETTINGS_H_ 
   24 #define EV3_JOINT_SETTINGS_H_ 
   26 #include <h4r_ev3_control/H4REv3Port.h> 
   28 namespace ev3_control {
 
   45         :joint_mode(EV3_JOINT_VELOCITY)
 
   48         Ev3JointMode joint_mode;
 
   49         std::string driver_name;
 
   50         std::vector<double> pid;
 
   73     bool load(
const Ev3HwSettings &settings, 
bool testOnly)
 
   83         ROS_INFO_STREAM(
"PID "<<settings.pid[0]
 
   84                               <<
" "<<settings.pid[1]
 
   85                               <<
" "<<settings.pid[2]);
 
  104         if(last_command == command)
 
  110             last_command=command;
 
  114         int cmd=(command*180.0/M_PI);
 
  120                 ROS_ERROR(
"NORMAL!");
 
  129                 ROS_ERROR(
"INVERSED!");
 
  133             switch(ev3settings.joint_mode)
 
  136             case Ev3JointSettings::EV3_JOINT_POSITION:
 
  152             case Ev3JointSettings::EV3_JOINT_VELOCITY:
 
  193             velocity_out=((double)vel)/180.0*M_PI;
 
  194             position_out=((double)pos)/180.0*M_PI;
 
bool speed(int &value)
Definition: H4REv3Port.h:329
 
bool setDutyCycleSP(int value)
Definition: H4REv3Port.h:279
 
Definition: ev3_joint_settings.h:29
 
Definition: ev3_joint_settings.h:41
 
bool setSpeedRegulation(Ev3Strings::Ev3Switch onoff)
Definition: H4REv3Port.h:289
 
bool setMotorCommand(Ev3Strings::Ev3MotorCommands command)
Definition: H4REv3Port.h:339
 
Definition: H4REv3Port.h:249
 
bool setSpeedSP(int value)
Definition: H4REv3Port.h:299
 
bool setMotorPolarity(Ev3Strings::Ev3Polarity pol)
Definition: H4REv3Port.h:349
 
bool setSpeedPID_Kp(unsigned int value)
Definition: H4REv3Port.h:359
 
bool isConnected()
Definition: H4REv3Port.cpp:49
 
bool setSpeedPID_Ki(unsigned int value)
Definition: H4REv3Port.h:369
 
bool setPositionSP(int value)
Definition: H4REv3Port.h:309
 
bool position(int &value)
Definition: H4REv3Port.h:319
 
bool setSpeedPID_Kd(unsigned int value)
Definition: H4REv3Port.h:379