#include <open_cr_module.h>

Public Member Functions | |
| void | initialize (const int control_cycle_msec, robotis_framework::Robot *robot) |
| OpenCRModule () | |
| void | process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, robotis_framework::Sensor * > sensors) |
| virtual | ~OpenCRModule () |
Public Member Functions inherited from robotis_framework::SensorModule | |
| std::string | getModuleName () |
| virtual | ~SensorModule () |
Private Member Functions | |
| double | getAccValue (int raw_value) |
| double | getGyroValue (int raw_value) |
| void | handleButton (const std::string &button_name) |
| void | handleVoltage (double present_volt) |
| double | lowPassFilter (double alpha, double x_new, double &x_old) |
| void | publishButtonMsg (const std::string &button_name) |
| void | publishDXLPowerMsg (unsigned int value) |
| void | publishIMU () |
| void | publishStatusMsg (unsigned int type, std::string msg) |
| void | queueThread () |
Private Attributes | |
| const double | ACCEL_FACTOR = 2.0 / 32768.0 |
| ros::Time | button_press_time_ |
| ros::Publisher | button_pub_ |
| std::map< std::string, bool > | buttons_ |
| std::map< std::string, ros::Time > | buttons_press_time_ |
| int | control_cycle_msec_ |
| const bool | DEBUG_PRINT |
| ros::Publisher | dxl_power_msg_pub_ |
| const double | G_ACC = 9.80665 |
| const double | GYRO_FACTOR = 2000.0 / 32800.0 |
| sensor_msgs::Imu | imu_msg_ |
| ros::Publisher | imu_pub_ |
| ros::Time | last_msg_time_ |
| double | present_volt_ |
| std::map< std::string, double > | previous_result_ |
| double | previous_volt_ |
| boost::thread | queue_thread_ |
| ros::Publisher | status_msg_pub_ |
Additional Inherited Members | |
Static Public Member Functions inherited from robotis_framework::Singleton< OpenCRModule > | |
| static void | destroyInstance () |
| static T * | getInstance () |
Public Attributes inherited from robotis_framework::SensorModule | |
| std::map< std::string, double > | result_ |
Protected Member Functions inherited from robotis_framework::Singleton< OpenCRModule > | |
| Singleton & | operator= (Singleton const &) |
| Singleton (Singleton const &) | |
| Singleton () | |
Protected Attributes inherited from robotis_framework::SensorModule | |
| std::string | module_name_ |
Definition at line 38 of file open_cr_module.h.
| robotis_op::OpenCRModule::OpenCRModule | ( | ) |
Definition at line 26 of file open_cr_module.cpp.
|
virtual |
Definition at line 69 of file open_cr_module.cpp.
|
private |
Definition at line 164 of file open_cr_module.cpp.
|
private |
Definition at line 158 of file open_cr_module.cpp.
|
private |
Definition at line 208 of file open_cr_module.cpp.
|
private |
Definition at line 259 of file open_cr_module.cpp.
|
virtual |
Implements robotis_framework::SensorModule.
Definition at line 74 of file open_cr_module.cpp.
|
private |
Definition at line 307 of file open_cr_module.cpp.
|
virtual |
Implements robotis_framework::SensorModule.
Definition at line 98 of file open_cr_module.cpp.
|
private |
Definition at line 250 of file open_cr_module.cpp.
|
private |
Definition at line 297 of file open_cr_module.cpp.
|
private |
Definition at line 169 of file open_cr_module.cpp.
|
private |
Definition at line 286 of file open_cr_module.cpp.
|
private |
Definition at line 80 of file open_cr_module.cpp.
|
private |
Definition at line 52 of file open_cr_module.h.
|
private |
Definition at line 72 of file open_cr_module.h.
|
private |
Definition at line 82 of file open_cr_module.h.
|
private |
Definition at line 70 of file open_cr_module.h.
|
private |
Definition at line 71 of file open_cr_module.h.
|
private |
Definition at line 68 of file open_cr_module.h.
|
private |
Definition at line 53 of file open_cr_module.h.
|
private |
Definition at line 84 of file open_cr_module.h.
|
private |
Definition at line 50 of file open_cr_module.h.
|
private |
Definition at line 51 of file open_cr_module.h.
|
private |
Definition at line 78 of file open_cr_module.h.
|
private |
Definition at line 81 of file open_cr_module.h.
|
private |
Definition at line 73 of file open_cr_module.h.
|
private |
Definition at line 76 of file open_cr_module.h.
|
private |
Definition at line 74 of file open_cr_module.h.
|
private |
Definition at line 75 of file open_cr_module.h.
|
private |
Definition at line 69 of file open_cr_module.h.
|
private |
Definition at line 83 of file open_cr_module.h.