open_cr_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 OP3_OPEN_CR_MODULE_H_
20 #define OP3_OPEN_CR_MODULE_H_
21 
22 #include <ros/ros.h>
23 #include <ros/callback_queue.h>
24 #include <std_msgs/String.h>
25 #include <sensor_msgs/Imu.h>
26 #include <boost/thread.hpp>
27 #include <eigen3/Eigen/Eigen>
28 
29 #include "robotis_controller_msgs/StatusMsg.h"
30 #include "robotis_controller_msgs/SyncWriteItem.h"
34 
35 namespace robotis_op
36 {
37 
39 {
40  public:
41  OpenCRModule();
42  virtual ~OpenCRModule();
43 
44  /* ROS Topic Callback Functions */
45  void initialize(const int control_cycle_msec, robotis_framework::Robot *robot);
46  void process(std::map<std::string, robotis_framework::Dynamixel *> dxls,
47  std::map<std::string, robotis_framework::Sensor *> sensors);
48 
49  private:
50  const double G_ACC = 9.80665;
51  const double GYRO_FACTOR = 2000.0 / 32800.0;
52  const double ACCEL_FACTOR = 2.0 / 32768.0;
53  const bool DEBUG_PRINT;
54 
55  void queueThread();
56 
57  double getGyroValue(int raw_value);
58  double getAccValue(int raw_value);
59  void publishIMU();
60 
61  void handleButton(const std::string &button_name);
62  void publishButtonMsg(const std::string &button_name);
63  void handleVoltage(double present_volt);
64  void publishStatusMsg(unsigned int type, std::string msg);
65  void publishDXLPowerMsg(unsigned int value);
66  double lowPassFilter(double alpha, double x_new, double &x_old);
67 
69  boost::thread queue_thread_;
70  std::map<std::string, bool> buttons_;
71  std::map<std::string, ros::Time> buttons_press_time_;
74  std::map<std::string, double> previous_result_;
76  double present_volt_;
77 
78  sensor_msgs::Imu imu_msg_;
79 
80  /* subscriber & publisher */
85 };
86 
87 }
88 
89 #endif /* OP3_OPEN_CR_MODULE_H_ */
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, robotis_framework::Sensor * > sensors)
ros::Publisher button_pub_
std::map< std::string, ros::Time > buttons_press_time_
ros::Publisher dxl_power_msg_pub_
void handleVoltage(double present_volt)
double lowPassFilter(double alpha, double x_new, double &x_old)
void publishStatusMsg(unsigned int type, std::string msg)
double getAccValue(int raw_value)
boost::thread queue_thread_
ros::Publisher status_msg_pub_
void publishButtonMsg(const std::string &button_name)
sensor_msgs::Imu imu_msg_
std::map< std::string, double > previous_result_
void publishDXLPowerMsg(unsigned int value)
void handleButton(const std::string &button_name)
double getGyroValue(int raw_value)
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
std::map< std::string, bool > buttons_


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