direct_control_module.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Author: Kayman */
18 
19 #ifndef DIRECT_CONTROL_MODULE_H_
20 #define DIRECT_CONTROL_MODULE_H_
21 
22 #include <boost/thread.hpp>
23 #include <eigen3/Eigen/Eigen>
24 
25 #include <ros/ros.h>
26 #include <ros/callback_queue.h>
27 #include <std_msgs/Empty.h>
28 #include <std_msgs/String.h>
29 #include <sensor_msgs/JointState.h>
30 
31 #include "robotis_controller_msgs/StatusMsg.h"
34 
36 
37 namespace robotis_op
38 {
39 
41 {
42  public:
44  virtual ~DirectControlModule();
45 
46  void initialize(const int control_cycle_msec, robotis_framework::Robot *robot);
47  void process(std::map<std::string, robotis_framework::Dynamixel *> dxls, std::map<std::string, double> sensors);
48 
49  void stop();
50  bool isRunning();
51 
52  void onModuleEnable();
53  void onModuleDisable();
54 
55  private:
56  enum TraIndex
57  {
58  Position = 0,
59  Velocity = 1,
62  };
63 
64  const int BASE_INDEX;
65  const int HEAD_INDEX;
67  const int RIGHT_ELBOW_INDEX;
69  const int LEFT_ELBOW_INDEX;
70 
71  /* ROS Topic Callback Functions */
72  void setJointCallback(const sensor_msgs::JointState::ConstPtr &msg);
73 
74  void queueThread();
75  void jointTraGeneThread();
76 
77  void startMoving();
78  void finishMoving();
79  void stopMoving();
80 
81  void publishStatusMsg(unsigned int type, std::string msg);
82 
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);
85 
86  std::map<std::string, bool> collision_;
87 
88  bool checkSelfCollision();
89  bool getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff);
90 
94 
96  boost::thread queue_thread_;
97  boost::thread *tra_gene_thread_;
98  boost::mutex tra_lock_;
100  const bool DEBUG;
107  double moving_time_;
109 
110  Eigen::MatrixXd target_position_;
111  Eigen::MatrixXd present_position_;
112  Eigen::MatrixXd goal_position_;
113  Eigen::MatrixXd goal_velocity_;
114  Eigen::MatrixXd goal_acceleration_;
115  Eigen::MatrixXd calc_joint_tra_;
116  Eigen::MatrixXd calc_joint_vel_tra_;
117  Eigen::MatrixXd calc_joint_accel_tra_;
118 
119  std::map<std::string, int> using_joint_name_;
120  std::map<int, double> max_angle_;
121  std::map<int, double> min_angle_;
122 
124  std::string last_msg_;
125 
127 };
128 
129 }
130 
131 #endif /* HEAD_CONTROL_MODULE_H_ */
void setJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
bool getDiff(OP3KinematicsDynamics *kinematics, int end_index, int base_index, double &diff)
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
OP3KinematicsDynamics * op3_kinematics_
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
std::map< std::string, int > using_joint_name_
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)
void publishStatusMsg(unsigned int type, std::string msg)
std::map< std::string, bool > collision_


op3_direct_control_module
Author(s): Kayman
autogenerated on Mon Jun 10 2019 14:41:17