19 #ifndef OP3_OPEN_CR_MODULE_H_ 20 #define OP3_OPEN_CR_MODULE_H_ 24 #include <std_msgs/String.h> 25 #include <sensor_msgs/Imu.h> 26 #include <boost/thread.hpp> 27 #include <eigen3/Eigen/Eigen> 29 #include "robotis_controller_msgs/StatusMsg.h" 30 #include "robotis_controller_msgs/SyncWriteItem.h" 46 void process(std::map<std::string, robotis_framework::Dynamixel *> dxls,
47 std::map<std::string, robotis_framework::Sensor *> sensors);
66 double lowPassFilter(
double alpha,
double x_new,
double &x_old);
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)
const double ACCEL_FACTOR
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)
ros::Time button_press_time_
std::map< std::string, bool > buttons_