24 #ifndef MANIPULATOR_BASE_MODULE_BASE_MODULE_H_ 25 #define MANIPULATOR_BASE_MODULE_BASE_MODULE_H_ 31 #include <std_msgs/Int16.h> 32 #include <std_msgs/Float64.h> 33 #include <std_msgs/String.h> 34 #include <geometry_msgs/Pose.h> 35 #include <boost/thread.hpp> 36 #include <yaml-cpp/yaml.h> 41 #include "robotis_controller_msgs/JointCtrlModule.h" 42 #include "robotis_controller_msgs/StatusMsg.h" 44 #include "manipulator_h_base_module_msgs/JointPose.h" 45 #include "manipulator_h_base_module_msgs/KinematicsPose.h" 47 #include "manipulator_h_base_module_msgs/GetJointPose.h" 48 #include "manipulator_h_base_module_msgs/GetKinematicsPose.h" 94 void parseIniPoseData(
const std::string &path);
95 void publishStatusMsg(
unsigned int type, std::string msg);
102 void initPoseMsgCallback(
const std_msgs::String::ConstPtr& msg);
103 void setModeMsgCallback(
const std_msgs::String::ConstPtr& msg);
105 void jointPoseMsgCallback(
const manipulator_h_base_module_msgs::JointPose::ConstPtr& msg);
106 void kinematicsPoseMsgCallback(
const manipulator_h_base_module_msgs::KinematicsPose::ConstPtr& msg);
108 bool getJointPoseCallback(manipulator_h_base_module_msgs::GetJointPose::Request &req,
109 manipulator_h_base_module_msgs::GetJointPose::Response &res);
110 bool getKinematicsPoseCallback(manipulator_h_base_module_msgs::GetKinematicsPose::Request &req,
111 manipulator_h_base_module_msgs::GetKinematicsPose::Response &res);
114 void generateInitPoseTrajProcess();
115 void generateJointTrajProcess();
116 void generateTaskTrajProcess();
120 void process(std::map<std::string, robotis_framework::Dynamixel *> dxls, std::map<std::string, double> sensors);
ROSCONSOLE_DECL void initialize()
BaseJointState * joint_state_
ros::Publisher status_msg_pub_
ros::Publisher set_ctrl_module_pub_
std::map< std::string, int > joint_name_to_id_
ManipulatorKinematicsDynamics * manipulator_
boost::thread * tra_gene_thread_
boost::thread queue_thread_