23 priv_node_handle_(
"~"),
24 is_joint_state_topic_(false),
25 is_cmd_vel_topic_(false),
27 wheel_separation_(0.0
f),
39 if (is_cmd_vel_topic_ ==
true)
57 result =
dxl_wb_->
init(port_name.c_str(), baud_rate, &log);
69 dynamixel = YAML::LoadFile(yaml_file.c_str());
71 if (dynamixel == NULL)
74 for (YAML::const_iterator it_file = dynamixel.begin(); it_file != dynamixel.end(); it_file++)
76 std::string name = it_file->first.as<std::string>();
82 YAML::Node item = dynamixel[name];
83 for (YAML::const_iterator it_item = item.begin(); it_item != item.end(); it_item++)
85 std::string item_name = it_item->first.as<std::string>();
86 int32_t value = it_item->second.as<int32_t>();
88 if (item_name ==
"ID")
91 ItemValue item_value = {item_name, value};
92 std::pair<std::string, ItemValue> info(name, item_value);
108 uint16_t model_number = 0;
109 result =
dxl_wb_->
ping((uint8_t)dxl.second, &model_number, &log);
113 ROS_ERROR(
"Can't find Dynamixel ID '%d'", dxl.second);
118 ROS_INFO(
"Name : %s, ID : %d, Model Number : %d", dxl.first.c_str(), dxl.second, model_number);
135 if (dxl.first == info.first)
137 if (info.second.item_name !=
"ID" && info.second.item_name !=
"Baud_Rate")
139 bool result =
dxl_wb_->
itemWrite((uint8_t)dxl.second, info.second.item_name.c_str(), info.second.value, &log);
143 ROS_ERROR(
"Failed to write value[%d] on items[%s] to Dynamixel[Name : %s, ID : %d]", info.second.value, info.second.item_name.c_str(), dxl.first.c_str(), dxl.second);
159 const char* log = NULL;
164 if (goal_position == NULL)
return false;
167 if (goal_velocity == NULL) goal_velocity =
dxl_wb_->
getItemInfo(it->second,
"Moving_Speed");
168 if (goal_velocity == NULL)
return false;
171 if (present_position == NULL)
return false;
174 if (present_velocity == NULL) present_velocity =
dxl_wb_->
getItemInfo(it->second,
"Present_Speed");
175 if (present_velocity == NULL)
return false;
178 if (present_current == NULL) present_current =
dxl_wb_->
getItemInfo(it->second,
"Present_Load");
179 if (present_current == NULL)
return false;
194 const char* log = NULL;
246 const char* log = NULL;
248 int32_t get_position[dxl_name.size()];
250 uint8_t id_array[dxl_name.size()];
253 for (
auto const& name:dxl_name)
285 for(uint8_t index = 0; index < id_cnt; index++)
295 uint32_t read_position;
339 const char* log = NULL;
341 dynamixel_workbench_msgs::DynamixelState dynamixel_state[
dynamixel_.size()];
353 dynamixel_state[id_cnt].name = dxl.first;
354 dynamixel_state[id_cnt].id = (uint8_t)dxl.second;
356 id_array[id_cnt++] = (uint8_t)dxl.second;
409 for(uint8_t index = 0; index < id_cnt; index++)
411 dynamixel_state[index].present_current = get_current[index];
412 dynamixel_state[index].present_velocity = get_velocity[index];
413 dynamixel_state[index].present_position = get_position[index];
420 uint16_t length_of_data =
control_items_[
"Present_Position"]->data_length +
423 uint32_t get_all_data[length_of_data];
425 for (
auto const& dxl:dynamixel_)
437 dynamixel_state[dxl_cnt].present_current =
DXL_MAKEWORD(get_all_data[4], get_all_data[5]);
438 dynamixel_state[dxl_cnt].present_velocity =
DXL_MAKEWORD(get_all_data[2], get_all_data[3]);
439 dynamixel_state[dxl_cnt].present_position =
DXL_MAKEWORD(get_all_data[0], get_all_data[1]);
474 double position = 0.0;
475 double velocity = 0.0;
509 const char* log = NULL;
512 int32_t dynamixel_velocity[
dynamixel_.size()];
514 const uint8_t LEFT = 0;
515 const uint8_t RIGHT = 1;
517 double robot_lin_vel = msg->linear.x;
518 double robot_ang_vel = msg->angular.z;
527 rpm = modelInfo->
rpm;
528 id_array[id_cnt++] = (uint8_t)dxl.second;
534 double velocity_constant_value = 1 / (
wheel_radius_ * rpm * 0.10472);
543 if (wheel_velocity[LEFT] == 0.0
f) dynamixel_velocity[LEFT] = 0;
544 else if (wheel_velocity[LEFT] < 0.0
f) dynamixel_velocity[LEFT] = ((-1.0f) * wheel_velocity[LEFT]) * velocity_constant_value + 1023;
545 else if (wheel_velocity[LEFT] > 0.0
f) dynamixel_velocity[LEFT] = (wheel_velocity[LEFT] * velocity_constant_value);
547 if (wheel_velocity[RIGHT] == 0.0
f) dynamixel_velocity[RIGHT] = 0;
548 else if (wheel_velocity[RIGHT] < 0.0
f) dynamixel_velocity[RIGHT] = ((-1.0f) * wheel_velocity[RIGHT] * velocity_constant_value) + 1023;
549 else if (wheel_velocity[RIGHT] > 0.0
f) dynamixel_velocity[RIGHT] = (wheel_velocity[RIGHT] * velocity_constant_value);
553 dynamixel_velocity[LEFT] = wheel_velocity[LEFT] * velocity_constant_value;
554 dynamixel_velocity[RIGHT] = wheel_velocity[RIGHT] * velocity_constant_value;
559 if (wheel_velocity[LEFT] == 0.0
f) dynamixel_velocity[LEFT] = 0;
560 else if (wheel_velocity[LEFT] < 0.0
f) dynamixel_velocity[LEFT] = ((-1.0f) * wheel_velocity[LEFT]) * velocity_constant_value + 1023;
561 else if (wheel_velocity[LEFT] > 0.0
f) dynamixel_velocity[LEFT] = (wheel_velocity[LEFT] * velocity_constant_value);
563 if (wheel_velocity[RIGHT] == 0.0
f) dynamixel_velocity[RIGHT] = 0;
564 else if (wheel_velocity[RIGHT] < 0.0
f) dynamixel_velocity[RIGHT] = ((-1.0f) * wheel_velocity[RIGHT] * velocity_constant_value) + 1023;
565 else if (wheel_velocity[RIGHT] > 0.0
f) dynamixel_velocity[RIGHT] = (wheel_velocity[RIGHT] * velocity_constant_value);
581 const char* log = NULL;
586 int32_t dynamixel_position[
dynamixel_.size()];
588 static uint32_t point_cnt = 0;
589 static uint32_t position_cnt = 0;
593 id_array[id_cnt] = (uint8_t)
dynamixel_[joint];
599 for (uint8_t index = 0; index < id_cnt; index++)
609 if (position_cnt >=
jnt_tra_msg_->points[point_cnt].positions.size())
644 ROS_ERROR(
"Failed to get Present Position");
646 for (
auto const& joint:msg->joint_names)
648 ROS_INFO(
"'%s' is ready to move", joint.c_str());
657 while(cnt < msg->points.size())
659 std::vector<WayPoint> goal;
660 for (std::vector<int>::size_type id_num = 0; id_num < msg->points[cnt].positions.size(); id_num++)
662 wp.
position = msg->points[cnt].positions.at(id_num);
664 if (msg->points[cnt].velocities.size() != 0) wp.
velocity = msg->points[cnt].velocities.at(id_num);
667 if (msg->points[cnt].accelerations.size() != 0) wp.
acceleration = msg->points[cnt].accelerations.at(id_num);
675 trajectory_msgs::JointTrajectoryPoint jnt_tra_point_msg;
677 for (uint8_t id_num = 0; id_num < id_cnt; id_num++)
679 jnt_tra_point_msg.positions.push_back(goal[id_num].position);
680 jnt_tra_point_msg.velocities.push_back(goal[id_num].velocity);
681 jnt_tra_point_msg.accelerations.push_back(goal[id_num].acceleration);
692 double move_time = 0.0f;
693 if (cnt == 0) move_time = msg->points[cnt].time_from_start.toSec();
694 else move_time = msg->points[cnt].time_from_start.toSec() - msg->points[cnt-1].time_from_start.toSec();
701 std::vector<WayPoint> way_point;
702 trajectory_msgs::JointTrajectoryPoint jnt_tra_point_msg;
704 for (
double index = 0.0; index < move_time; index = index +
write_period_)
708 for (uint8_t id_num = 0; id_num < id_cnt; id_num++)
710 jnt_tra_point_msg.positions.push_back(way_point[id_num].position);
711 jnt_tra_point_msg.velocities.push_back(way_point[id_num].velocity);
712 jnt_tra_point_msg.accelerations.push_back(way_point[id_num].acceleration);
716 jnt_tra_point_msg.positions.clear();
717 jnt_tra_point_msg.velocities.clear();
718 jnt_tra_point_msg.accelerations.clear();
725 ROS_INFO(
"Succeeded to get joint trajectory!");
730 ROS_WARN(
"Please check joint_name");
740 dynamixel_workbench_msgs::DynamixelCommand::Response &res)
746 std::string item_name = req.addr_name;
747 int32_t value = req.value;
753 ROS_ERROR(
"Failed to write value[%d] on items[%s] to Dynamixel[ID : %d]", value, item_name.c_str(), id);
756 res.comm_result = result;
761 int main(
int argc,
char **argv)
763 ros::init(argc, argv,
"dynamixel_workbench_controllers");
766 std::string port_name =
"/dev/ttyUSB0";
767 uint32_t baud_rate = 57600;
771 ROS_ERROR(
"Please set '-port_name' and '-baud_rate' arguments for connected Dynamixels");
777 baud_rate = atoi(argv[2]);
784 std::string yaml_file = node_handle.
param<std::string>(
"dynamixel_info",
"");
786 result = dynamixel_controller.
initWorkbench(port_name, baud_rate);
803 ROS_ERROR(
"Please check Dynamixel ID or BaudRate");
810 ROS_ERROR(
"Please check control table (http://emanual.robotis.com/#control-table)");
824 ROS_ERROR(
"Failed to set Dynamixel SDK Handler");
bool initSDKHandlers(void)
#define SYNC_WRITE_HANDLER_FOR_GOAL_POSITION
ros::Subscriber trajectory_sub_
bool torqueOff(uint8_t id, const char **log=NULL)
void writeCallback(const ros::TimerEvent &)
void publish(const boost::shared_ptr< M > &message) const
void commandVelocityCallback(const geometry_msgs::Twist::ConstPtr &msg)
void setJointNum(uint8_t joint_num)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
JointTrajectory * jnt_tra_
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
bool getDynamixelsInfo(const std::string yaml_file)
double getPublishPeriod()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int32_t convertRadian2Value(uint8_t id, float radian)
bool itemWrite(uint8_t id, const char *item_name, int32_t data, const char **log=NULL)
bool torqueOn(uint8_t id, const char **log=NULL)
bool syncWrite(uint8_t index, int32_t *data, const char **log=NULL)
bool readRegister(uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log=NULL)
std::vector< std::pair< std::string, ItemValue > > dynamixel_info_
const char * getModelName(uint8_t id, const char **log=NULL)
trajectory_msgs::JointTrajectory * jnt_tra_msg_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
float convertValue2Current(uint8_t id, int16_t value)
DynamixelWorkbench * dxl_wb_
ros::Subscriber cmd_vel_sub_
float convertValue2Load(int16_t value)
std::vector< WayPoint > getJointWayPoint(double tick)
bool is_joint_state_topic_
bool initDynamixels(void)
bool dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req, dynamixel_workbench_msgs::DynamixelCommand::Response &res)
bool initControlItems(void)
bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log=NULL)
std::map< std::string, const ControlItem * > control_items_
const ControlItem * getItemInfo(uint8_t id, const char *item_name, const char **log=NULL)
bool ping(uint8_t id, uint16_t *get_model_number, const char **log=NULL)
bool initWorkbench(const std::string port_name, const uint32_t baud_rate)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
float convertValue2Radian(uint8_t id, int32_t value)
void init(double move_time, double control_time, std::vector< WayPoint > start, std::vector< WayPoint > goal)
bool getSyncReadData(uint8_t index, int32_t *data, const char **log=NULL)
sensor_msgs::JointState joint_state_msg_
ros::Publisher dynamixel_state_list_pub_
void readCallback(const ros::TimerEvent &)
bool getPresentPosition(std::vector< std::string > dxl_name)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
#define SYNC_WRITE_HANDLER_FOR_GOAL_VELOCITY
ros::NodeHandle priv_node_handle_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const ModelInfo * getModelInfo(uint8_t id, const char **log=NULL)
void publishCallback(const ros::TimerEvent &)
void initSubscriber(void)
std::map< std::string, uint32_t > dynamixel_
bool loadDynamixels(void)
ros::Publisher joint_states_pub_
#define ROS_INFO_THROTTLE(rate,...)
int main(int argc, char **argv)
std::vector< WayPoint > pre_goal_
dynamixel_workbench_msgs::DynamixelStateList dynamixel_state_list_
bool syncRead(uint8_t index, const char **log=NULL)
ros::ServiceServer dynamixel_command_server_
void trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
float convertValue2Velocity(uint8_t id, int32_t value)
float getProtocolVersion(void)
#define SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT