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 #ifdef REACTIVE_RATE_FUNCTION 18 #define CONTROL_WAIT_HZ (50) 19 #define CONTROL_ACTIVE_HZ (200) 21 #define CONTROL_HZ (200) 29 typedef dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig>
RECONFIG_TYPE;
52 std::vector<std::string>
split(
const std::string& input,
char delimiter)
54 std::istringstream stream(input);
57 std::vector<std::string> result;
58 while (std::getline(stream, field, delimiter)) {
59 result.push_back(field);
67 std::string topic = header.at(
"topic");
68 const std_msgs::UInt16ConstPtr& msg =
event.getMessage();
69 uint16_t set_gain_data = msg->data;
74 std::vector<std::string> topic_list =
split(topic,
'/');
75 std::string joint_name = topic_list[ topic_list.size()-2 ];
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 ){
80 set_req_data.
dxl_id = it->get_dxl_id();
81 set_req_data.
gain = set_gain_data;
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 ){
119 config.torque_enable =
true;
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;
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");
144 dxl_pos_name = ( joint_name +
"/dxl_position");
146 temp_name = ( joint_name +
"/temp");
148 gain_name = ( joint_name +
"/gain");
155 for( std::vector<JOINT_CONTROL>::iterator it=driver->
joints.begin() ; it!=driver->
joints.end() ; ++it ){
157 dynamic_reconfigure::Server<crane_x7_msgs::ServoParameterConfig>::CallbackType
f;
159 server->setCallback(f);
160 reconfig_srv.push_back( std::unique_ptr<RECONFIG_TYPE>(server) );
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;
171 std_msgs::Float64 current_out;
172 std_msgs::Int16 dxl_pos_out;
173 std_msgs::Float64 temp_out;
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 );
183 dxl_pos_out.data = it->get_dxl_pos();
184 dxl_pos_it->publish( dxl_pos_out );
187 temp_out.data = it->get_temprature();
188 temp_it->publish( temp_out );
216 int main(
int argc,
char* argv[] )
221 std::string config_ns_str;
222 nhPrivate.
getParam(
"config_ns", config_ns_str);
227 if( !setting.
load() ){
233 std::string errorlog;
234 if( crane_x7.
get_error( errorlog ) > 0 ){
235 ROS_INFO(
"Initialize error (%s)",errorlog.c_str());
240 driver_addr = &crane_x7;
245 #ifdef REACTIVE_RATE_FUNCTION 247 ros::Rate rate_active( CONTROL_ACTIVE_HZ );
256 uint32_t prev_tempCount = 0;
257 bool read_temp_flg =
false;
270 if( crane_x7.
tempCount != prev_tempCount ){
271 read_temp_flg =
true;
274 read_temp_flg =
false;
278 crane_x7.
read( t, d );
280 crane_x7.
write( t, d );
296 std::string errorlog;
297 while( crane_x7.
get_error( errorlog ) > 0 ){
302 #ifdef REACTIVE_RATE_FUNCTION void set_watchdog_all(uint8_t value)
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
int main(int argc, char *argv[])
void init_reconfigure(DXLPORT_CONTROL *driver)
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
static std::vector< std::unique_ptr< RECONFIG_TYPE > > reconfig_srv
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())
#define MSEC2DXL_WATCHDOG(msec)
static std::vector< ros::Publisher > temp_pub
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)
ROSCPP_DECL const std::string & getName()
static std::vector< ros::Publisher > current_pub
void startup_motion(void)
uint16_t moving_threshold
void write(ros::Time, ros::Duration)
std::map< std::string, std::string > M_string
bool is_change_positions(void)
void publish_topic_data(DXLPORT_CONTROL *driver, bool temp_flg)
static std_msgs::String lasterror_out
void init_topics(DXLPORT_CONTROL *driver, ros::NodeHandle nh)
struct SET_GAIN_QUEUE ST_SET_GAIN_QUEUE
void set_goal_current_all(uint16_t current)
static std::vector< ros::Subscriber > gain_sub
void gainCallback(const ros::MessageEvent< std_msgs::UInt16 const > &event)
static std::queue< ST_SET_GAIN_QUEUE > set_gain_request
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
void set_param_delay_time(uint8_t dxl_id, int val)
void effort_limitter(void)
#define DXL_WATCHDOG_RESET_VALUE
uint8_t return_delay_time
void set_param_moving_threshold(uint8_t dxl_id, int val)
std::vector< std::string > split(const std::string &input, char delimiter)
bool read(ros::Time, ros::Duration)
void write_joint_param(DXLPORT_CONTROL &driver, ST_JOINT_PARAM set_param)
bool getParam(const std::string &key, std::string &s) const
void set_param_vel_gain(uint8_t dxl_id, int p, int i)
ROSCPP_DECL void shutdown()
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
ros::Time getTime() const
std::string self_check(void)
static std::queue< ST_JOINT_PARAM > set_joint_param_request
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)
SET_GAIN_QUEUE(const SET_GAIN_QUEUE &src)
void SigintHandler(int sig)