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>
17 #define REACTIVE_RATE_FUNCTION //指示姿勢に変化がない場合に制御周期を落としてCPU負荷を下げる機能
18 #ifdef REACTIVE_RATE_FUNCTION
19 #define CONTROL_WAIT_HZ (50)
20 #define CONTROL_ACTIVE_HZ (200)
22 #define CONTROL_HZ (200)
30 typedef dynamic_reconfigure::Server<sciurus17_msgs::ServoParameterConfig>
RECONFIG_TYPE;
53 std::vector<std::string>
split(
const std::string& input,
char delimiter)
55 std::istringstream stream(input);
58 std::vector<std::string> result;
59 while (std::getline(stream, field, delimiter)) {
60 result.push_back(field);
68 std::string topic =
header.at(
"topic");
69 const std_msgs::UInt16ConstPtr& msg =
event.getMessage();
70 uint16_t set_gain_data = msg->data;
75 std::vector<std::string> topic_list =
split(topic,
'/');
76 std::string joint_name = topic_list[ topic_list.size()-2 ];
79 if( it->get_joint_name() == joint_name ){
81 set_req_data.
dxl_id = it->get_dxl_id();
82 set_req_data.
gain = set_gain_data;
109 if( it->get_dxl_id() ==
id ){
120 config.torque_enable =
true;
135 std::string current_name;
136 std::string dxl_pos_name;
137 std::string temp_name;
138 std::string gain_name;
139 std::string joint_name;
141 for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
142 joint_name = it->get_joint_name();
143 current_name = ( joint_name +
"/current");
145 dxl_pos_name = ( joint_name +
"/dxl_position");
147 temp_name = ( joint_name +
"/temp");
149 gain_name = ( joint_name +
"/gain");
156 for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
158 dynamic_reconfigure::Server<sciurus17_msgs::ServoParameterConfig>::CallbackType
f;
160 server->setCallback(
f);
161 reconfig_srv.push_back( std::unique_ptr<RECONFIG_TYPE>(server) );
168 std::vector<ros::Publisher>::iterator current_it;
169 std::vector<ros::Publisher>::iterator dxl_pos_it;
170 std::vector<ros::Publisher>::iterator temp_it;
172 std_msgs::Float64 current_out;
173 std_msgs::Int16 dxl_pos_out;
174 std_msgs::Float64 temp_out;
180 for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
181 current_out.data = it->get_current();
182 current_it->publish( current_out );
184 dxl_pos_out.data = it->get_dxl_pos();
185 dxl_pos_it->publish( dxl_pos_out );
188 temp_out.data = it->get_temprature();
189 temp_it->publish( temp_out );
197 uint8_t dxl_id = set_param.
dxl_id;
217 int main(
int argc,
char* argv[] )
225 if( !setting.
load() ){
231 std::string errorlog;
232 if( sciurus17.
get_error( errorlog ) > 0 ){
233 ROS_INFO(
"Initialize error (%s)",errorlog.c_str());
243 #ifdef REACTIVE_RATE_FUNCTION
254 uint32_t prev_tempCount = 0;
255 bool read_temp_flg =
false;
268 if( sciurus17.
tempCount != prev_tempCount ){
269 read_temp_flg =
true;
272 read_temp_flg =
false;
277 if( sciurus17.
read( t,
d ) ){
295 std::string errorlog;
296 while( sciurus17.
get_error( errorlog ) > 0 ){
301 #ifdef REACTIVE_RATE_FUNCTION