ev3_joint_settings.h
1 /*
2  * This file (ev3_joint_settings.h) is part of h4r_ev3_manager.
3  * Date: 16.11.2015
4  *
5  * Author: Christian Holl
6  * http://github.com/Hacks4ROS
7  *
8  * h4r_ev3_manager is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * h4r_ev3_manager is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with h4r_ev3_joint_setup. If not, see <http://www.gnu.org/licenses/>.
20  *
21  */
22 
23 #ifndef EV3_JOINT_SETTINGS_H_
24 #define EV3_JOINT_SETTINGS_H_
25 
26 #include <h4r_ev3_control/H4REv3Port.h>
27 
28 namespace ev3_control {
30 {
31 
32 public:
33 
34  typedef enum
35  {
36  EV3_JOINT_OFF,
37  EV3_JOINT_POSITION,
38  EV3_JOINT_VELOCITY,
39  } Ev3JointMode;
40 
42  {
43  public:
45  :joint_mode(EV3_JOINT_VELOCITY)
46  {}
47 
48  Ev3JointMode joint_mode;
49  std::string driver_name;
50  std::vector<double> pid;
51  };
52 
53 
54  H4REv3Motor port;
55  Ev3HwSettings ev3settings;
56 
57  double command;
58  double last_command;
59  double velocity_out;
60  double position_out;
61  double effort_out; //not supported by ev3 afaik but needed for joint state handle
62 
63  Ev3JointSettings(const std::string &out_port)
64  :port(out_port)
65  ,command(0)
66  ,last_command(0)
67  ,velocity_out(0)
68  ,position_out(0)
69  ,effort_out(0)
70  {}
71 
72 
73  bool load(const Ev3HwSettings &settings, bool testOnly)
74  {
75 
76 
77  if(!testOnly)
78  {
79  port.setMotorCommand(Ev3Strings::EV3MOTORCOMMANDS_RESET);
80  }
81 
82 
83  ROS_INFO_STREAM("PID "<<settings.pid[0]
84  <<" "<<settings.pid[1]
85  <<" "<<settings.pid[2]);
86  //Setting motor PIDs
87  port.setSpeedPID_Kp(settings.pid[0]);
88  port.setSpeedPID_Ki(settings.pid[1]);
89  port.setSpeedPID_Kd(settings.pid[2]);
90 
91 
92  return true;
93  }
94 
95  bool write()
96  {
97 
98  if(!port.isConnected())
99  {
100  last_command = 0; //Reset last command for user pluging it in again.
101  return false;
102  }
103 
104  if(last_command == command)
105  {
106  return true;
107  }
108  else
109  {
110  last_command=command;
111  }
112 
113 
114  int cmd=(command*180.0/M_PI);
115 
116  if(cmd>0)
117  {
118  if(!port.setMotorPolarity(Ev3Strings::EV3POLARITY_NORMAL))
119  {
120  ROS_ERROR("NORMAL!");
121  return false;
122  }
123  }
124  else if(cmd<0)
125  {
126  cmd=-cmd;
127  if(!port.setMotorPolarity(Ev3Strings::EV3POLARITY_INVERSED))
128  {
129  ROS_ERROR("INVERSED!");
130  return false;
131  }
132  }
133  switch(ev3settings.joint_mode)
134  {
135 
136  case Ev3JointSettings::EV3_JOINT_POSITION:
137 
138  if
139  (
140  port.setDutyCycleSP(100)+
141  port.setPositionSP(cmd)+
142  port.setSpeedRegulation(Ev3Strings::EV3SWITCH_OFF)+
143  port.setMotorCommand(Ev3Strings::EV3MOTORCOMMANDS_RUN_TO_ABS_POS)
144  !=4
145  )
146  {
147  return false;
148  }
149 
150  break;
151 
152  case Ev3JointSettings::EV3_JOINT_VELOCITY:
153  {
154  if(cmd==0)
155  {
156  return port.setMotorCommand(Ev3Strings::EV3MOTORCOMMANDS_STOP);
157  }
158  else
159  {
160 
161  if
162  (
163  port.setDutyCycleSP(100)+
164  port.setSpeedSP(cmd)+
165  port.setSpeedRegulation(Ev3Strings::EV3SWITCH_ON)+
166  port.setMotorCommand(Ev3Strings::EV3MOTORCOMMANDS_RUN_FOREVER)
167  != 4
168  )
169  return false;
170  }
171  }
172  break;
173 
174  default:
175  break;
176  }
177 
178  return true;
179  }
180 
181  bool read()
182  {
183  if(!port.isConnected())
184  return false;
185 
186  int pos;
187  int vel;
188 
189  if(
190  port.position(pos)+port.speed(vel) == 2
191  )
192  {
193  velocity_out=((double)vel)/180.0*M_PI;
194  position_out=((double)pos)/180.0*M_PI;
195  return true;
196  }
197  else
198  {
199  return false;
200  }
201  }
202 
203 };
204 
205 }
206 
207 #endif /* EV3_JOINT_SETTINGS_H_ */
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