hardware.cpp
Go to the documentation of this file.
1 #include <signal.h>
2 #include <ros/ros.h>
3 #include <ros/console.h>
6 #include <std_msgs/Int32.h>
7 #include <std_msgs/Int16.h>
8 #include <std_msgs/UInt16.h>
9 #include <std_msgs/Int8.h>
10 #include <std_msgs/String.h>
11 #include <std_msgs/Float64.h>
12 #include <sstream>
13 #include <queue>
14 
15 /* ROS rate setting */
16 //#define REACTIVE_RATE_FUNCTION
17 #ifdef REACTIVE_RATE_FUNCTION
18 #define CONTROL_WAIT_HZ (50)
19 #define CONTROL_ACTIVE_HZ (200)
20 #else
21 #define CONTROL_HZ (200)
22 #endif
23 
24 static std_msgs::String lasterror_out;
25 static std::vector<ros::Publisher> current_pub;
26 static std::vector<ros::Publisher> dxl_position_pub;
27 static std::vector<ros::Publisher> temp_pub;
28 static std::vector<ros::Subscriber> gain_sub;
29 typedef dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig> RECONFIG_TYPE;
30 static std::vector<std::unique_ptr<RECONFIG_TYPE>> reconfig_srv;
32 
33 typedef struct SET_GAIN_QUEUE
34 {
36  {
37  dxl_id = 0;
38  gain = 0;
39  }
41  {
42  dxl_id = src.dxl_id;
43  gain = src.gain;
44  }
45  uint8_t dxl_id;
46  uint16_t gain;
48 static std::queue<ST_SET_GAIN_QUEUE> set_gain_request;
49 
50 static std::queue<ST_JOINT_PARAM> set_joint_param_request;
51 
52 std::vector<std::string> split(const std::string& input, char delimiter)
53 {
54  std::istringstream stream(input);
55 
56  std::string field;
57  std::vector<std::string> result;
58  while (std::getline(stream, field, delimiter)) {
59  result.push_back(field);
60  }
61  return result;
62 }
63 
65 {
66  const ros::M_string& header = event.getConnectionHeader();
67  std::string topic = header.at("topic");
68  const std_msgs::UInt16ConstPtr& msg = event.getMessage();
69  uint16_t set_gain_data = msg->data;
70  if( set_gain_data >= DXL_PGAIN_MAX ){
71  set_gain_data = DXL_PGAIN_MAX;
72  }
73 
74  std::vector<std::string> topic_list = split(topic,'/');
75  std::string joint_name = topic_list[ topic_list.size()-2 ];// Parent topic name
76 
77  for( std::vector<JOINT_CONTROL>::iterator it=driver_addr->joints.begin() ; it!=driver_addr->joints.end() ; ++it ){
78  if( it->get_joint_name() == joint_name ){
79  ST_SET_GAIN_QUEUE set_req_data;
80  set_req_data.dxl_id = it->get_dxl_id();
81  set_req_data.gain = set_gain_data;
82  set_gain_request.push( set_req_data );
83  break;
84  }
85  }
86 }
87 void reconfigureCallback(crane_x7_msgs::ServoParameterConfig &config, uint32_t level, uint8_t id )
88 {
89  ST_JOINT_PARAM set_req_data;
90  set_req_data.dxl_id = id;
91  set_req_data.return_delay_time = config.return_delay_time;
92  set_req_data.drive_mode = config.drive_mode;
93  set_req_data.operation_mode = config.operation_mode;
94  set_req_data.moving_threshold = config.moving_threshold;
95  set_req_data.homing_offset = config.homing_offset;
96  set_req_data.temprature_limit = config.temprature_limit;
97  set_req_data.max_vol_limit = config.max_vol_limit;
98  set_req_data.min_vol_limit = config.min_vol_limit;
99  set_req_data.current_limit = config.current_limit;
100  set_req_data.torque_enable = config.torque_enable?1:0;
101  set_req_data.velocity_i_gain = config.velocity_i_gain;
102  set_req_data.velocity_p_gain = config.velocity_p_gain;
103  set_req_data.position_d_gain = config.position_d_gain;
104  set_req_data.position_i_gain = config.position_i_gain;
105  set_req_data.position_p_gain = config.position_p_gain;
106  if( level != 0 ){
107  for( std::vector<JOINT_CONTROL>::iterator it=driver_addr->joints.begin() ; it!=driver_addr->joints.end() ; ++it ){
108  if( it->get_dxl_id() == id ){
109  ST_JOINT_PARAM load_data = it->get_joint_param();
110  config.return_delay_time = load_data.return_delay_time;
111  config.drive_mode = load_data.drive_mode;
112  config.operation_mode = load_data.operation_mode;
113  config.moving_threshold = load_data.moving_threshold;
114  config.homing_offset = load_data.homing_offset;
115  config.temprature_limit = load_data.temprature_limit;
116  config.max_vol_limit = load_data.max_vol_limit;
117  config.min_vol_limit = load_data.min_vol_limit;
118  config.current_limit = load_data.current_limit;
119  config.torque_enable = true;
120  config.velocity_i_gain = load_data.velocity_i_gain;
121  config.velocity_p_gain = load_data.velocity_p_gain;
122  config.position_d_gain = load_data.position_d_gain;
123  config.position_i_gain = load_data.position_i_gain;
124  config.position_p_gain = DXL_DEFAULT_PGAIN;
125  }
126  }
127  }else{
128  set_joint_param_request.push( set_req_data );
129  }
130 }
131 
133 {
134  std::string current_name;
135  std::string dxl_pos_name;
136  std::string temp_name;
137  std::string gain_name;
138  std::string joint_name;
139 
140  for( std::vector<JOINT_CONTROL>::iterator it=driver->joints.begin() ; it!=driver->joints.end() ; ++it ){
141  joint_name = it->get_joint_name();
142  current_name = ( joint_name + "/current");
143  current_pub.push_back( nh.advertise<std_msgs::Float64>(current_name, 10) );
144  dxl_pos_name = ( joint_name + "/dxl_position");
145  dxl_position_pub.push_back( nh.advertise<std_msgs::Int16>(dxl_pos_name, 10) );
146  temp_name = ( joint_name + "/temp");
147  temp_pub.push_back( nh.advertise<std_msgs::Float64>(temp_name, 10) );
148  gain_name = ( joint_name + "/gain");
149  gain_sub.push_back( nh.subscribe(gain_name, 100, gainCallback) );
150  }
151 }
152 
154 {
155  for( std::vector<JOINT_CONTROL>::iterator it=driver->joints.begin() ; it!=driver->joints.end() ; ++it ){
156  RECONFIG_TYPE* server = new RECONFIG_TYPE( "~/"+it->get_joint_name() );
157  dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig>::CallbackType f;
158  f = boost::bind(reconfigureCallback, _1, _2, it->get_dxl_id());
159  server->setCallback(f);
160  reconfig_srv.push_back( std::unique_ptr<RECONFIG_TYPE>(server) );
161  }
162 }
163 
164 void publish_topic_data( DXLPORT_CONTROL *driver, bool temp_flg )
165 {
166  int joint_index;
167  std::vector<ros::Publisher>::iterator current_it;
168  std::vector<ros::Publisher>::iterator dxl_pos_it;
169  std::vector<ros::Publisher>::iterator temp_it;
170 
171  std_msgs::Float64 current_out;
172  std_msgs::Int16 dxl_pos_out;
173  std_msgs::Float64 temp_out;
174 
175  current_it = current_pub.begin();
176  dxl_pos_it = dxl_position_pub.begin();
177  temp_it = temp_pub.begin();
178 
179  for( std::vector<JOINT_CONTROL>::iterator it=driver->joints.begin() ; it!=driver->joints.end() ; ++it ){
180  current_out.data = it->get_current();
181  current_it->publish( current_out );
182  ++current_it;
183  dxl_pos_out.data = it->get_dxl_pos();
184  dxl_pos_it->publish( dxl_pos_out );
185  ++dxl_pos_it;
186  if( temp_flg ){
187  temp_out.data = it->get_temprature();
188  temp_it->publish( temp_out );
189  ++temp_it;
190  }
191  }
192 }
193 
195 {
196  uint8_t dxl_id = set_param.dxl_id;
197 
198  driver.set_param_delay_time( dxl_id, set_param.return_delay_time );
199  driver.set_param_drive_mode( dxl_id, set_param.drive_mode );
200  driver.set_param_ope_mode( dxl_id, set_param.operation_mode );
201  driver.set_param_home_offset( dxl_id, set_param.homing_offset );
202  driver.set_param_moving_threshold( dxl_id, set_param.moving_threshold );
203  driver.set_param_temp_limit( dxl_id, set_param.temprature_limit );
204  driver.set_param_vol_limit( dxl_id, set_param.max_vol_limit, set_param.min_vol_limit );
205  driver.set_param_current_limit( dxl_id, set_param.current_limit );
206  driver.set_param_vel_gain( dxl_id, set_param.velocity_p_gain, set_param.velocity_i_gain );
207  driver.set_param_pos_gain( dxl_id, set_param.position_p_gain, set_param.position_i_gain, set_param.position_d_gain );
208  driver.set_torque( dxl_id, (set_param.torque_enable?true:false) );
209 }
210 
211 void SigintHandler( int sig )
212 {
213  ros::shutdown();
214 }
215 
216 int main( int argc, char* argv[] )
217 {
219  ros::NodeHandle nh;
220  ros::NodeHandle nhPrivate("~");
221  std::string config_ns_str;
222  nhPrivate.getParam("config_ns", config_ns_str);
223  ros::NodeHandle nhConfig(config_ns_str);
224  signal(SIGINT, SigintHandler);
225 
226  CONTROL_SETTING setting( nhConfig );
227  if( !setting.load() ){
228  return -1;
229  }
230 
231  DXLPORT_CONTROL crane_x7( nhPrivate, setting );
232  if( !crane_x7.get_init_stat() ){
233  std::string errorlog;
234  if( crane_x7.get_error( errorlog ) > 0 ){
235  ROS_INFO("Initialize error (%s)",errorlog.c_str());
236  }
237  return -1;
238  }
239  controller_manager::ControllerManager cm( &crane_x7, nh );
240  driver_addr = &crane_x7;
241 
242  ros::Publisher lasterror_pub = nhPrivate.advertise<std_msgs::String>("lasterror", 10);
243  init_topics( &crane_x7, nhPrivate );
244 
245 #ifdef REACTIVE_RATE_FUNCTION
246  ros::Rate rate_wait( CONTROL_WAIT_HZ );
247  ros::Rate rate_active( CONTROL_ACTIVE_HZ );
248 #else
249  ros::Rate rate( CONTROL_HZ );
250 #endif
252  spinner.start();
253 
254  ros::Time t = crane_x7.getTime();
255  ros::Duration d = crane_x7.getDuration(t);
256  uint32_t prev_tempCount = 0;
257  bool read_temp_flg = false;
258 
259  ROS_INFO( "%s", crane_x7.self_check().c_str() );
260  init_reconfigure( &crane_x7 );
261 
263  crane_x7.startup_motion();
264  crane_x7.set_watchdog_all( MSEC2DXL_WATCHDOG(1000) ); //1秒の間,無通信で停止
265 
266  while( ros::ok() ){
267  d = crane_x7.getDuration(t);
268  t = crane_x7.getTime();
269 
270  if( crane_x7.tempCount != prev_tempCount ){
271  read_temp_flg = true;
272  prev_tempCount = crane_x7.tempCount;
273  }else{
274  read_temp_flg = false;
275  }
276  publish_topic_data( &crane_x7, read_temp_flg );
277 
278  crane_x7.read( t, d );
279  cm.update( t, d );
280  crane_x7.write( t, d );
281 
282  while( set_gain_request.size() > 0 ){
283  ST_SET_GAIN_QUEUE gain_data = set_gain_request.front();
284  crane_x7.set_gain( gain_data.dxl_id, gain_data.gain );
285  set_gain_request.pop();
286  }
287 
288  // Dynamixelとの通信タイムアウトを防ぐため、
289  // write_joint_param()は1制御ループで1回のみ実行する
290  if( set_joint_param_request.size() > 0 ){
291  write_joint_param( crane_x7, set_joint_param_request.front() );
293  }
294  crane_x7.effort_limitter();
295 
296  std::string errorlog;
297  while( crane_x7.get_error( errorlog ) > 0 ){ // error log check
298  lasterror_out.data = errorlog;
299  lasterror_pub.publish( lasterror_out );
300  }
301 
302 #ifdef REACTIVE_RATE_FUNCTION
303  if( crane_x7.is_change_positions() ){
304  rate_active.sleep();
305  }else{
306  rate_wait.sleep();
307  }
308 #else
309  rate.sleep();
310 #endif
311  }
312 
314  crane_x7.set_goal_current_all( 0 );
315  spinner.stop();
316 
317  return 0;
318 }
void set_watchdog_all(uint8_t value)
d
void set_param_home_offset(uint8_t dxl_id, int val)
void set_param_pos_gain_all(int p, int i, int d)
static std::vector< ros::Publisher > dxl_position_pub
Definition: hardware.cpp:26
uint16_t current_limit
Definition: joint_control.h:99
int main(int argc, char *argv[])
Definition: hardware.cpp:216
void init_reconfigure(DXLPORT_CONTROL *driver)
Definition: hardware.cpp:153
std::string::size_type get_error(std::string &errorlog)
void publish(const boost::shared_ptr< M > &message) const
dynamic_reconfigure::Server< crane_x7_msgs::ServoParameterConfig > RECONFIG_TYPE
Definition: hardware.cpp:29
f
static std::vector< std::unique_ptr< RECONFIG_TYPE > > reconfig_srv
Definition: hardware.cpp:30
bool set_torque(uint8_t dxl_id, bool torque)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int32_t homing_offset
Definition: joint_control.h:95
#define MSEC2DXL_WATCHDOG(msec)
static std::vector< ros::Publisher > temp_pub
Definition: hardware.cpp:27
uint8_t temprature_limit
Definition: joint_control.h:96
void set_param_drive_mode(uint8_t dxl_id, int val)
#define DXL_DEFAULT_PGAIN
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void set_param_vol_limit(uint8_t dxl_id, int max, int min)
uint8_t torque_enable
ROSCPP_DECL const std::string & getName()
static std::vector< ros::Publisher > current_pub
Definition: hardware.cpp:25
void startup_motion(void)
uint16_t moving_threshold
Definition: joint_control.h:94
void write(ros::Time, ros::Duration)
void spinner()
std::map< std::string, std::string > M_string
bool is_change_positions(void)
uint16_t position_p_gain
#define DXL_FREE_DGAIN
void publish_topic_data(DXLPORT_CONTROL *driver, bool temp_flg)
Definition: hardware.cpp:164
static std_msgs::String lasterror_out
Definition: hardware.cpp:24
void init_topics(DXLPORT_CONTROL *driver, ros::NodeHandle nh)
Definition: hardware.cpp:132
#define ROS_INFO(...)
struct SET_GAIN_QUEUE ST_SET_GAIN_QUEUE
void set_goal_current_all(uint16_t current)
uint16_t gain
Definition: hardware.cpp:46
#define DXL_FREE_PGAIN
ROSCPP_DECL bool ok()
static std::vector< ros::Subscriber > gain_sub
Definition: hardware.cpp:28
bool get_init_stat(void)
void gainCallback(const ros::MessageEvent< std_msgs::UInt16 const > &event)
Definition: hardware.cpp:64
static std::queue< ST_SET_GAIN_QUEUE > set_gain_request
Definition: hardware.cpp:48
void set_gain(uint8_t dxl_id, uint16_t gain)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void set_param_current_limit(uint8_t dxl_id, int val)
static DXLPORT_CONTROL * driver_addr
Definition: hardware.cpp:31
#define DXL_PGAIN_MAX
uint16_t position_i_gain
uint8_t max_vol_limit
Definition: joint_control.h:97
bool sleep()
uint16_t velocity_p_gain
void set_param_delay_time(uint8_t dxl_id, int val)
uint8_t min_vol_limit
Definition: joint_control.h:98
void effort_limitter(void)
#define DXL_WATCHDOG_RESET_VALUE
uint8_t return_delay_time
Definition: joint_control.h:91
void set_param_moving_threshold(uint8_t dxl_id, int val)
uint16_t velocity_i_gain
std::vector< std::string > split(const std::string &input, char delimiter)
Definition: hardware.cpp:52
bool read(ros::Time, ros::Duration)
void write_joint_param(DXLPORT_CONTROL &driver, ST_JOINT_PARAM set_param)
Definition: hardware.cpp:194
bool getParam(const std::string &key, std::string &s) const
uint16_t position_d_gain
#define CONTROL_HZ
Definition: hardware.cpp:21
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
uint8_t drive_mode
Definition: joint_control.h:92
ROSCPP_DECL void shutdown()
uint8_t dxl_id
Definition: hardware.cpp:45
uint8_t operation_mode
Definition: joint_control.h:93
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
ros::Time getTime() const
std::string self_check(void)
#define DXL_FREE_IGAIN
static std::queue< ST_JOINT_PARAM > set_joint_param_request
Definition: hardware.cpp:50
std::vector< JOINT_CONTROL > joints
void set_param_ope_mode(uint8_t dxl_id, int val)
void set_param_temp_limit(uint8_t dxl_id, int val)
ros::Duration getDuration(ros::Time t) const
void set_param_pos_gain(uint8_t dxl_id, int p, int i, int d)
void reconfigureCallback(crane_x7_msgs::ServoParameterConfig &config, uint32_t level, uint8_t id)
Definition: hardware.cpp:87
SET_GAIN_QUEUE(const SET_GAIN_QUEUE &src)
Definition: hardware.cpp:40
void SigintHandler(int sig)
Definition: hardware.cpp:211


crane_x7_control
Author(s): Hiroyuki Nomura , Geoffrey Biggs
autogenerated on Mon Mar 1 2021 03:18:36