26 : control_cycle_msec_(0),
35 default_moving_time_(0.5),
36 default_moving_angle_(30),
37 check_collision_(true),
41 RIGHT_END_EFFECTOR_INDEX(21),
43 LEFT_END_EFFECTOR_INDEX(22),
65 for (std::map<std::string, robotis_framework::Dynamixel*>::iterator it = robot->
dxls_.begin();
66 it != robot->
dxls_.end(); it++)
68 std::string joint_name = it->first;
122 publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_ERROR,
"Not Enable");
127 int waiting_count = 0;
131 if(++waiting_count > 100)
133 ROS_ERROR(
"present joint angle is not updated");
154 for (
int ix = 0; ix < msg->name.size(); ix++)
156 std::string joint_name = msg->name[ix];
157 std::map<std::string, int>::iterator joint_it =
using_joint_name_.find(joint_name);
161 double target_position = 0.0;
162 int joint_index = joint_it->second;
165 target_position = msg->position[ix];
180 std::cout <<
"joint : " << joint_name <<
", Index : " << joint_index <<
", Angle : " << msg->position[ix]
187 goal_acceleration_.coeffRef(0, joint_index) = 0.0;
198 for ( std::map<std::string, int>::iterator joint_index_it =
using_joint_name_.begin();
201 std::string joint_name = joint_index_it->first;
202 int index = joint_index_it->second;
212 double diff_length = 0.0;
214 if(result ==
true && diff_length < 0.075)
219 if(result ==
true && diff_length < 0.075)
229 std::map<std::string, double> sensors)
237 for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it =
result_.begin();
238 state_it !=
result_.end(); state_it++)
240 std::string joint_name = state_it->first;
244 std::map<std::string, robotis_framework::Dynamixel*>::iterator dxl_it = dxls.find(joint_name);
245 if (dxl_it != dxls.end())
246 _dxl = dxl_it->second;
292 for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it =
result_.begin();
293 state_it !=
result_.end(); state_it++)
295 std::string joint_name = state_it->first;
311 for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it =
result_.begin();
312 state_it !=
result_.end(); state_it++)
314 std::string joint_name = state_it->first;
319 result_[joint_name]->goal_position_ = goal_position;
369 publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_INFO,
"Head movement is finished.");
372 std::cout <<
"Trajectory End" << std::endl;
385 publishStatusMsg(robotis_controller_msgs::StatusMsg::STATUS_WARN,
"Stop Module.");
404 double pos_end,
double vel_end,
double accel_end,
405 double smp_time,
double mov_time)
407 Eigen::MatrixXd poly_matrix(3, 3);
408 Eigen::MatrixXd poly_vector(3, 1);
415 poly_vector << pos_end - pos_start - vel_start * mov_time - accel_start * pow(mov_time, 2) / 2, vel_end - vel_start
416 - accel_start * mov_time, accel_end - accel_start;
418 Eigen::MatrixXd poly_coeff = poly_matrix.inverse() * poly_vector;
420 int all_time_steps = round(mov_time / smp_time + 1);
422 Eigen::MatrixXd time = Eigen::MatrixXd::Zero(all_time_steps, 1);
423 Eigen::MatrixXd minimum_jer_tra = Eigen::MatrixXd::Zero(all_time_steps, 3);
425 for (
int step = 0; step < all_time_steps; step++)
426 time.coeffRef(step, 0) = step * smp_time;
428 for (
int step = 0; step < all_time_steps; step++)
431 minimum_jer_tra.coeffRef(step, 0) = pos_start + vel_start * time.coeff(step, 0)
437 minimum_jer_tra.coeffRef(step, 1) = vel_start + accel_start * time.coeff(step, 0)
442 minimum_jer_tra.coeffRef(step, 2) = accel_start + 6 * poly_coeff.coeff(0, 0) * time.coeff(step, 0)
447 return minimum_jer_tra;
453 bool collision_result =
false;
458 double diff_length = 0.0;
462 if(result ==
true && diff_length < collision_boundary)
465 ROS_WARN_STREAM_THROTTLE(1,
"Self Collision : RIGHT_ARM and BASE | " << diff_length <<
" / " << collision_boundary);
470 collision_result =
true;
479 if(result ==
true && diff_length < collision_boundary)
482 ROS_WARN_STREAM_THROTTLE(1,
"Self Collision : RIGHT_ELBOW and BASE | " << diff_length <<
" / " << collision_boundary);
486 collision_result =
true;
495 if(result ==
true && diff_length < collision_boundary)
503 collision_result =
true;
512 if(result ==
true && diff_length < collision_boundary)
515 ROS_WARN_STREAM_THROTTLE(1,
"Self Collision : LEFT_ELBOW and BASE | " << diff_length <<
" / " << collision_boundary);
519 collision_result =
true;
522 if(collision_result ==
false &&
DEBUG ==
true)
523 ROS_WARN(
"============================================");
525 return collision_result;
535 Eigen::Vector3d diff_vec = base_position - end_position;
536 diff_vec.coeffRef(2) = 0;
538 diff = diff_vec.norm();
540 ROS_WARN_STREAM_COND(
DEBUG,
"\nBase Position [" << base_position.coeff(0) <<
", " << base_position.coeff(1) <<
", " << base_position.coeff(2) <<
"] \n" 541 <<
"End Position [" << end_position.coeff(0) <<
", " << end_position.coeff(1) <<
", " << end_position.coeff(2) <<
"] \n" 542 <<
"Diff : " << diff);
561 catch(std::exception &e)
563 std::cout <<
"All step tile : " << all_time_steps << std::endl;
564 std::cout << e.what() << std::endl;
568 for (std::map<std::string, robotis_framework::DynamixelState *>::iterator state_it =
result_.begin();
569 state_it !=
result_.end(); state_it++)
571 std::string joint_name = state_it->first;
580 Eigen::MatrixXd tra =
calcMinimumJerkTraPVA(ini_pos, ini_vel, ini_accel, tar_value, 0.0, 0.0, smp_time,
608 robotis_controller_msgs::StatusMsg status_msg;
609 status_msg.header.stamp = now;
610 status_msg.type = type;
611 status_msg.module_name =
"Direct Control";
612 status_msg.status_msg = msg;
Eigen::MatrixXd calc_joint_vel_tra_
void setJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
bool checkSelfCollision()
std::map< std::string, DynamixelState * > result_
bool getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff)
void publish(const boost::shared_ptr< M > &message) const
Eigen::MatrixXd calc_joint_accel_tra_
const int RIGHT_END_EFFECTOR_INDEX
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Eigen::MatrixXd goal_velocity_
boost::thread * tra_gene_thread_
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
LinkData * op3_link_data_[ALL_JOINT_ID+1]
boost::thread queue_thread_
void calcForwardKinematics(int joint_ID)
ControlMode control_mode_
std::map< std::string, Dynamixel * > dxls_
OP3KinematicsDynamics * op3_kinematics_
void jointTraGeneThread()
double default_moving_time_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setCallbackQueue(CallbackQueueInterface *queue)
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
std::map< std::string, int > using_joint_name_
Eigen::MatrixXd calc_joint_tra_
#define ROS_WARN_STREAM_COND(cond, args)
double default_moving_angle_
const int RIGHT_ELBOW_INDEX
Eigen::MatrixXd calcMinimumJerkTraPVA(double pos_start, double vel_start, double accel_start, double pos_end, double vel_end, double accel_end, double smp_time, double mov_time)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
ros::Publisher status_msg_pub_
double powDI(double a, int b)
virtual ~DirectControlModule()
Eigen::MatrixXd position_
DynamixelState * dxl_state_
Eigen::MatrixXd goal_acceleration_
#define ROS_INFO_THROTTLE(rate,...)
LinkData * getLinkData(const std::string link_name)
void publishStatusMsg(unsigned int type, std::string msg)
std::map< std::string, bool > collision_
const int LEFT_END_EFFECTOR_INDEX
const int LEFT_ELBOW_INDEX
Eigen::MatrixXd target_position_
Eigen::MatrixXd goal_position_
Eigen::MatrixXd present_position_