head_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 HEAD_CONTROL_MODULE_H_
20 #define HEAD_CONTROL_MODULE_H_
21 
22 #include <cstdlib>
23 #include <ctime>
24 #include <boost/thread.hpp>
25 #include <eigen3/Eigen/Eigen>
26 
27 #include <ros/ros.h>
28 #include <ros/callback_queue.h>
29 #include <std_msgs/Empty.h>
30 #include <std_msgs/String.h>
31 #include <sensor_msgs/JointState.h>
32 
33 #include "robotis_controller_msgs/StatusMsg.h"
36 
37 namespace robotis_op
38 {
39 
41 {
42  public:
44  virtual ~HeadControlModule();
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
57  {
58  NoScan = 0,
59  TopLeft = 1,
62  TopRight = 4,
63  };
64 
65  /* ROS Topic Callback Functions */
66  void setHeadJointCallback(const sensor_msgs::JointState::ConstPtr &msg);
67  void setHeadJointOffsetCallback(const sensor_msgs::JointState::ConstPtr &msg);
68  void setHeadScanCallback(const std_msgs::String::ConstPtr &msg);
69 
70  void queueThread();
71  void jointTraGeneThread();
72  void setHeadJoint(const sensor_msgs::JointState::ConstPtr &msg, bool is_offset);
73  bool checkAngleLimit(const int joint_index, double &goal_position);
74  void generateScanTra(const int head_direction);
75 
76  void startMoving();
77  void finishMoving();
78  void stopMoving();
79 
80  void publishStatusMsg(unsigned int type, std::string msg);
81 
82  Eigen::MatrixXd calcMinimumJerkTraPVA(double pos_start, double vel_start, double accel_start, double pos_end,
83  double vel_end, double accel_end, double smp_time, double mov_time);
84 
86  boost::thread queue_thread_;
87  boost::thread *tra_gene_thread_;
88  boost::mutex tra_lock_;
90  const bool DEBUG;
92  bool is_moving_;
95  double moving_time_;
98  double angle_unit_;
99 
100  Eigen::MatrixXd target_position_;
101  Eigen::MatrixXd current_position_;
102  Eigen::MatrixXd goal_position_;
103  Eigen::MatrixXd goal_velocity_;
104  Eigen::MatrixXd goal_acceleration_;
105  Eigen::MatrixXd calc_joint_tra_;
106  Eigen::MatrixXd calc_joint_vel_tra_;
107  Eigen::MatrixXd calc_joint_accel_tra_;
108 
109  std::map<std::string, int> using_joint_name_;
110  std::map<int, double> max_angle_;
111  std::map<int, double> min_angle_;
112 
114  std::string last_msg_;
115 };
116 
117 }
118 
119 #endif /* HEAD_CONTROL_MODULE_H_ */
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< std::string, int > using_joint_name_
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
void setHeadJointCallback(const sensor_msgs::JointState::ConstPtr &msg)
bool checkAngleLimit(const int joint_index, double &goal_position)
std::map< int, double > max_angle_
std::map< int, double > min_angle_
void setHeadJointOffsetCallback(const sensor_msgs::JointState::ConstPtr &msg)
void setHeadJoint(const sensor_msgs::JointState::ConstPtr &msg, bool is_offset)
void generateScanTra(const int head_direction)
void setHeadScanCallback(const std_msgs::String::ConstPtr &msg)
void publishStatusMsg(unsigned int type, std::string msg)


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