19 #ifndef DIRECT_CONTROL_MODULE_H_ 20 #define DIRECT_CONTROL_MODULE_H_ 22 #include <boost/thread.hpp> 23 #include <eigen3/Eigen/Eigen> 27 #include <std_msgs/Empty.h> 28 #include <std_msgs/String.h> 29 #include <sensor_msgs/JointState.h> 31 #include "robotis_controller_msgs/StatusMsg.h" 47 void process(std::map<std::string, robotis_framework::Dynamixel *> dxls, std::map<std::string, double> sensors);
83 Eigen::MatrixXd
calcMinimumJerkTraPVA(
double pos_start,
double vel_start,
double accel_start,
double pos_end,
84 double vel_end,
double accel_end,
double smp_time,
double mov_time);
Eigen::MatrixXd calc_joint_vel_tra_
void setJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
bool checkSelfCollision()
bool getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff)
Eigen::MatrixXd calc_joint_accel_tra_
const int RIGHT_END_EFFECTOR_INDEX
std::map< int, double > min_angle_
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)
boost::thread queue_thread_
OP3KinematicsDynamics * op3_kinematics_
void jointTraGeneThread()
double default_moving_time_
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
std::map< std::string, int > using_joint_name_
Eigen::MatrixXd calc_joint_tra_
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)
std::map< int, double > max_angle_
ros::Publisher status_msg_pub_
virtual ~DirectControlModule()
Eigen::MatrixXd goal_acceleration_
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_