khi_robot_driver.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Kawasaki Heavy Industries, LTD.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef KHI_ROBOT_DRIVER_H
36 #define KHI_ROBOT_DRIVER_H
37 
38 #include <string>
39 #include <khi_robot_msgs/KhiRobotCmd.h>
40 
41 namespace khi_robot_control
42 {
43 #define KHI_MAX_CONTROLLER 8
44 #define KHI_MAX_ARM 2
45 #define KHI_MAX_JOINT 18
46 #define KHI_MAX_SIG_SIZE 512
47 
48 struct KhiRobotArmData
49 {
50  int jt_num;
51  std::string name[KHI_MAX_JOINT];
52  int type[KHI_MAX_JOINT];
53  double cmd[KHI_MAX_JOINT];
54  double pos[KHI_MAX_JOINT];
55  double vel[KHI_MAX_JOINT];
56  double eff[KHI_MAX_JOINT];
57  double home[KHI_MAX_JOINT];
58 };
59 
60 struct KhiRobotData
61 {
62  std::string robot_name;
63  int arm_num;
64  KhiRobotArmData arm[KHI_MAX_ARM];
65 };
66 
67 struct KhiRobotControllerInfo
68 {
69  int state;
70  int state_trigger;
71  std::string ip_address;
72  double period;
73 };
74 
76 {
77  STATE_MIN = -1,
79  CONNECTING,
81  ACTIVATING,
90 };
91 const static std::string KhiRobotStateName[STATE_MAX] =
92 {
93  "INIT",
94  "CONNECTING",
95  "INACTIVE",
96  "ACTIVATING",
97  "ACTIVE",
98  "HOLDED",
99  "DEACTIVATING",
100  "DISCONNECTING",
101  "DISCONNECTED",
102  "ERROR",
103  "NOT_REGISTERED"
104 };
105 
107 {
108  TRIGGER_MIN = -1,
114 };
115 const static std::string KhiRobotStateTriggerName[TRIGGER_MAX] =
116 {
117  "NONE",
118  "HOLD",
119  "RESTART",
120  "QUIT"
121 };
122 
124 {
125 public:
127  {
128  for ( int cno = 0; cno < KHI_MAX_CONTROLLER; cno++ )
129  {
130  cont_info[cno].state = INIT;
132  cont_info[cno].ip_address = "127.0.0.1";
133  }
134 
135  driver_name = __func__;
136  }
137 
138  int getState( const int& cont_no )
139  {
140  if ( ( cont_no < 0 ) || ( cont_no > KHI_MAX_CONTROLLER ) ) { return NOT_REGISTERED; }
141  else { return cont_info[cont_no].state; }
142  }
143 
144  std::string getStateName( const int& cont_no )
145  {
146  int state;
147  std::string name = "";
148 
149  state = getState( cont_no );
150  if ( ( state > STATE_MIN ) && ( state < STATE_MAX ) )
151  {
152  name = KhiRobotStateName[state];
153  }
154 
155  return name;
156  }
157 
158  bool setState( const int& cont_no, const int& state )
159  {
160  if ( !contLimitCheck( cont_no, KHI_MAX_CONTROLLER ) ) { return false; }
161 
162  if ( ( state <= STATE_MIN ) || ( state >= STATE_MAX ) )
163  {
164  return false;
165  }
166  else
167  {
168  if ( cont_info[cont_no].state != state )
169  {
170  infoPrint( "State %d: %s -> %s", cont_no, KhiRobotStateName[cont_info[cont_no].state].c_str(), KhiRobotStateName[state].c_str() );
171  cont_info[cont_no].state = state;
172  }
173  return true;
174  }
175  }
176 
177  bool isTransitionState( const int& cont_no )
178  {
179  int state;
180 
181  state = getState( cont_no );
182  if ( ( state == CONNECTING ) || ( state == ACTIVATING ) || ( state == DEACTIVATING ) || ( state == DISCONNECTING ) )
183  {
184  return true;
185  }
186  else
187  {
188  return false;
189  }
190  }
191 
192  int getStateTrigger( const int& cont_no )
193  {
194  int state_trigger;
195 
196  if ( ( cont_no < 0 ) || ( cont_no > KHI_MAX_CONTROLLER ) ) { return NONE; }
197  else
198  {
199  state_trigger = cont_info[cont_no].state_trigger;
200  cont_info[cont_no].state_trigger = NONE;
201  return state_trigger;
202  }
203  }
204 
205  bool setStateTrigger( const int& cont_no, const int& state_trigger )
206  {
207  if ( !contLimitCheck( cont_no, KHI_MAX_CONTROLLER ) ) { return false; }
208 
209  if ( ( state_trigger <= TRIGGER_MIN ) || ( state_trigger >= TRIGGER_MAX ) )
210  {
211  return false;
212  }
213  else
214  {
215  if ( cont_info[cont_no].state_trigger != NONE )
216  {
217  warnPrint( "State Trigger is already done %d: %s", cont_no, KhiRobotStateTriggerName[state_trigger].c_str() );
218  }
219  infoPrint( "State Trigger %d: %s", cont_no, KhiRobotStateTriggerName[state_trigger].c_str() );
220  cont_info[cont_no].state_trigger = state_trigger;
221  return true;
222  }
223  }
224 
225  bool contLimitCheck( const int& cont_no, const int& limit )
226  {
227  if ( ( cont_no < 0 ) || ( cont_no > KHI_MAX_CONTROLLER ) || ( cont_no > limit ) )
228  {
229  errorPrint( "contLimitCheck ERROR!" );
230  return false;
231  }
232  else
233  {
234  return true;
235  }
236  }
237 
238  void infoPrint( const char* format, ... )
239  {
240  char msg[512] = { 0 };
241  va_list ap;
242 
243  va_start( ap, format );
244  vsnprintf( msg, sizeof(msg), format, ap );
245  va_end( ap );
246  ROS_INFO( "[%s] %s", driver_name.c_str(), msg );
247  }
248 
249  void warnPrint( const char* format, ... )
250  {
251  char msg[512] = { 0 };
252  va_list ap;
253 
254  va_start( ap, format );
255  vsnprintf( msg, sizeof(msg), format, ap );
256  va_end( ap );
257  ROS_WARN( "[%s] %s", driver_name.c_str(), msg );
258  }
259 
260  void errorPrint( const char* format, ... )
261  {
262  char msg[512] = { 0 };
263  va_list ap;
264 
265  va_start( ap, format );
266  vsnprintf( msg, sizeof(msg), format, ap );
267  va_end( ap );
268  ROS_ERROR( "[%s] %s", driver_name.c_str(), msg );
269  }
270 
271  void jointPrint( std::string name, const KhiRobotData& data )
272  {
273  char msg[512] = { 0 };
274  char jt_val[16] = { 0 };
275  const double* value;
276 
277  snprintf( msg, sizeof(msg), "[%s]\t", name.c_str() );
278  for ( int ano = 0; ano < KHI_MAX_ARM; ano++ )
279  {
280  if ( name == std::string("write") ) { value = data.arm[ano].cmd; }
281  else { value = data.arm[ano].pos; }
282  for ( int jt = 0; jt < data.arm[ano].jt_num; jt++ )
283  {
284  snprintf( jt_val, sizeof(jt_val), "%.3lf\t", value[jt] );
285  strcat( msg, jt_val );
286  }
287  }
288  infoPrint( "[SIM]%s", msg );
289  }
290 
291  virtual ~KhiRobotDriver() {};
292  virtual bool initialize( const int& cont_no, const double& period, KhiRobotData& data, const bool in_simulation = false ) = 0;
293  virtual bool open( const int& cont_no, const std::string& ip_address, KhiRobotData& data ) = 0;
294  virtual bool close( const int& cont_no ) = 0;
295  virtual bool activate( const int& cont_no, KhiRobotData& data ) = 0;
296  virtual bool hold( const int& cont_no, const KhiRobotData& data ) = 0;
297  virtual bool deactivate( const int& cont_no, const KhiRobotData& data ) = 0;
298  virtual bool readData( const int& cont_no, KhiRobotData& data ) = 0;
299  virtual bool writeData( const int& cont_no, const KhiRobotData& data ) = 0;
300  virtual bool updateState( const int& cont_no, const KhiRobotData& data ) = 0;
301  virtual bool getPeriodDiff( const int& cont_no, double& diff ) = 0;
302  virtual bool commandHandler( khi_robot_msgs::KhiRobotCmd::Request& req, khi_robot_msgs::KhiRobotCmd::Response& res ) = 0;
303 
304 protected:
305  bool in_simulation;
306  std::string driver_name;
308  int return_code;
309  int error_code;
310 };
311 
312 } // namespace
313 
314 #endif // KHI_ROBOT_DRIVER_H
khi_robot_control::ERROR
@ ERROR
Definition: khi_robot_driver.h:119
khi_robot_control::KhiRobotDriver::return_code
int return_code
Definition: khi_robot_driver.h:340
khi_robot_control::KhiRobotArmData::jt_num
int jt_num
Definition: khi_robot_driver.h:82
khi_robot_control::KhiRobotDriver::open
virtual bool open(const int &cont_no, const std::string &ip_address, KhiRobotData &data)=0
khi_robot_control::KhiRobotDriver::initialize
virtual bool initialize(const int &cont_no, const double &period, KhiRobotData &data, const bool in_simulation=false)=0
khi_robot_control::NOT_REGISTERED
@ NOT_REGISTERED
Definition: khi_robot_driver.h:120
khi_robot_control::KhiRobotArmData::cmd
double cmd[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:85
msg
msg
khi_robot_control::CONNECTING
@ CONNECTING
Definition: khi_robot_driver.h:111
khi_robot_control::KhiRobotDriver::activate
virtual bool activate(const int &cont_no, KhiRobotData &data)=0
khi_robot_control::INACTIVE
@ INACTIVE
Definition: khi_robot_driver.h:112
khi_robot_control::KhiRobotDriver::close
virtual bool close(const int &cont_no)=0
khi_robot_control::STATE_MAX
@ STATE_MAX
Definition: khi_robot_driver.h:121
khi_robot_control::KhiRobotDriver::contLimitCheck
bool contLimitCheck(const int &cont_no, const int &limit)
Definition: khi_robot_driver.h:257
khi_robot_control::ACTIVATING
@ ACTIVATING
Definition: khi_robot_driver.h:113
khi_robot_control::KhiRobotControllerInfo::period
double period
Definition: khi_robot_driver.h:104
khi_robot_control::KhiRobotStateTriggerName
const static std::string KhiRobotStateTriggerName[TRIGGER_MAX]
Definition: khi_robot_driver.h:147
KHI_MAX_ARM
#define KHI_MAX_ARM
Definition: khi_robot_driver.h:76
khi_robot_control::KhiRobotDriver::isTransitionState
bool isTransitionState(const int &cont_no)
Definition: khi_robot_driver.h:209
khi_robot_control::KhiRobotDriver::hold
virtual bool hold(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::KhiRobotData::arm_num
int arm_num
Definition: khi_robot_driver.h:95
khi_robot_control::KhiRobotControllerInfo::ip_address
std::string ip_address
Definition: khi_robot_driver.h:103
khi_robot_control::KhiRobotDriver::jointPrint
void jointPrint(std::string name, const KhiRobotData &data)
Definition: khi_robot_driver.h:303
khi_robot_control::KhiRobotDriver::in_simulation
bool in_simulation
Definition: khi_robot_driver.h:337
khi_robot_control::KhiRobotDriver::setState
bool setState(const int &cont_no, const int &state)
Definition: khi_robot_driver.h:190
khi_robot_control::KhiRobotDriver::commandHandler
virtual bool commandHandler(khi_robot_msgs::KhiRobotCmd::Request &req, khi_robot_msgs::KhiRobotCmd::Response &res)=0
khi_robot_control::KhiRobotDriver::writeData
virtual bool writeData(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::INIT
@ INIT
Definition: khi_robot_driver.h:110
khi_robot_control::HOLD
@ HOLD
Definition: khi_robot_driver.h:142
khi_robot_control::KhiRobotDriver::~KhiRobotDriver
virtual ~KhiRobotDriver()
Definition: khi_robot_driver.h:323
data
data
khi_robot_control::TRIGGER_MAX
@ TRIGGER_MAX
Definition: khi_robot_driver.h:145
khi_robot_control::KhiRobotDriver::deactivate
virtual bool deactivate(const int &cont_no, const KhiRobotData &data)=0
khi_robot_control::RESTART
@ RESTART
Definition: khi_robot_driver.h:143
khi_robot_control::KhiRobotControllerInfo
Definition: khi_robot_driver.h:99
khi_robot_control::QUIT
@ QUIT
Definition: khi_robot_driver.h:144
khi_robot_control::KhiRobotDriver::warnPrint
void warnPrint(const char *format,...)
Definition: khi_robot_driver.h:281
khi_robot_control::KhiRobotArmData::home
double home[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:89
khi_robot_control::KhiRobotArmData::pos
double pos[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:86
khi_robot_control::KhiRobotArmData::type
int type[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:84
khi_robot_control::ACTIVE
@ ACTIVE
Definition: khi_robot_driver.h:114
khi_robot_control::KhiRobotDriver::getPeriodDiff
virtual bool getPeriodDiff(const int &cont_no, double &diff)=0
khi_robot_control::KhiRobotData::robot_name
std::string robot_name
Definition: khi_robot_driver.h:94
khi_robot_control::KhiRobotData::arm
KhiRobotArmData arm[KHI_MAX_ARM]
Definition: khi_robot_driver.h:96
khi_robot_control::KhiRobotDriver::getStateTrigger
int getStateTrigger(const int &cont_no)
Definition: khi_robot_driver.h:224
khi_robot_control::KhiRobotDriver::getStateName
std::string getStateName(const int &cont_no)
Definition: khi_robot_driver.h:176
khi_robot_control::KhiRobotDriver::infoPrint
void infoPrint(const char *format,...)
Definition: khi_robot_driver.h:270
khi_robot_control::KhiRobotArmData::eff
double eff[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:88
khi_robot_control::KhiRobotDriver::cont_info
KhiRobotControllerInfo cont_info[KHI_MAX_CONTROLLER]
Definition: khi_robot_driver.h:339
ROS_WARN
#define ROS_WARN(...)
khi_robot_control::TRIGGER_MIN
@ TRIGGER_MIN
Definition: khi_robot_driver.h:140
khi_robot_control::KhiRobotDriver::setStateTrigger
bool setStateTrigger(const int &cont_no, const int &state_trigger)
Definition: khi_robot_driver.h:237
KHI_MAX_JOINT
#define KHI_MAX_JOINT
Definition: khi_robot_driver.h:77
khi_robot_control::KhiRobotDriver::errorPrint
void errorPrint(const char *format,...)
Definition: khi_robot_driver.h:292
khi_robot_control::KhiRobotData
Definition: khi_robot_driver.h:92
khi_robot_control::KhiRobotStateName
const static std::string KhiRobotStateName[STATE_MAX]
Definition: khi_robot_driver.h:123
khi_robot_control::KhiRobotControllerInfo::state_trigger
int state_trigger
Definition: khi_robot_driver.h:102
KHI_MAX_CONTROLLER
#define KHI_MAX_CONTROLLER
Definition: khi_robot_driver.h:75
khi_robot_control
Definition: khi_robot_client.h:42
khi_robot_control::DEACTIVATING
@ DEACTIVATING
Definition: khi_robot_driver.h:116
khi_robot_control::KhiRobotState
KhiRobotState
Definition: khi_robot_driver.h:107
khi_robot_control::KhiRobotControllerInfo::state
int state
Definition: khi_robot_driver.h:101
khi_robot_control::STATE_MIN
@ STATE_MIN
Definition: khi_robot_driver.h:109
ROS_ERROR
#define ROS_ERROR(...)
khi_robot_control::KhiRobotArmData::name
std::string name[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:83
khi_robot_control::NONE
@ NONE
Definition: khi_robot_driver.h:141
khi_robot_control::KhiRobotDriver::driver_name
std::string driver_name
Definition: khi_robot_driver.h:338
khi_robot_control::DISCONNECTED
@ DISCONNECTED
Definition: khi_robot_driver.h:118
khi_robot_control::KhiRobotDriver::readData
virtual bool readData(const int &cont_no, KhiRobotData &data)=0
khi_robot_control::HOLDED
@ HOLDED
Definition: khi_robot_driver.h:115
khi_robot_control::KhiRobotArmData::vel
double vel[KHI_MAX_JOINT]
Definition: khi_robot_driver.h:87
khi_robot_control::KhiRobotDriver::error_code
int error_code
Definition: khi_robot_driver.h:341
khi_robot_control::KhiRobotStateTrigger
KhiRobotStateTrigger
Definition: khi_robot_driver.h:138
ROS_INFO
#define ROS_INFO(...)
khi_robot_control::KhiRobotDriver
Definition: khi_robot_driver.h:155
khi_robot_control::KhiRobotDriver::getState
int getState(const int &cont_no)
Definition: khi_robot_driver.h:170
khi_robot_control::DISCONNECTING
@ DISCONNECTING
Definition: khi_robot_driver.h:117
khi_robot_control::KhiRobotDriver::KhiRobotDriver
KhiRobotDriver()
Definition: khi_robot_driver.h:158
khi_robot_control::KhiRobotDriver::updateState
virtual bool updateState(const int &cont_no, const KhiRobotData &data)=0


khi_robot_control
Author(s): nakamichi_d
autogenerated on Sat Oct 21 2023 02:54:50