Public Member Functions | Private Member Functions | Private Attributes | List of all members
robotis_op::OpenCRModule Class Reference

#include <open_cr_module.h>

Inheritance diagram for robotis_op::OpenCRModule:
Inheritance graph
[legend]

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::Timebuttons_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 >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::SensorModule
std::string module_name_
 

Detailed Description

Definition at line 38 of file open_cr_module.h.

Constructor & Destructor Documentation

robotis_op::OpenCRModule::OpenCRModule ( )

Definition at line 26 of file open_cr_module.cpp.

robotis_op::OpenCRModule::~OpenCRModule ( )
virtual

Definition at line 69 of file open_cr_module.cpp.

Member Function Documentation

double robotis_op::OpenCRModule::getAccValue ( int  raw_value)
private

Definition at line 164 of file open_cr_module.cpp.

double robotis_op::OpenCRModule::getGyroValue ( int  raw_value)
private

Definition at line 158 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::handleButton ( const std::string &  button_name)
private

Definition at line 208 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::handleVoltage ( double  present_volt)
private

Definition at line 259 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual

Implements robotis_framework::SensorModule.

Definition at line 74 of file open_cr_module.cpp.

double robotis_op::OpenCRModule::lowPassFilter ( double  alpha,
double  x_new,
double &  x_old 
)
private

Definition at line 307 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, robotis_framework::Sensor * >  sensors 
)
virtual

Implements robotis_framework::SensorModule.

Definition at line 98 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::publishButtonMsg ( const std::string &  button_name)
private

Definition at line 250 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::publishDXLPowerMsg ( unsigned int  value)
private

Definition at line 297 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::publishIMU ( )
private

Definition at line 169 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::publishStatusMsg ( unsigned int  type,
std::string  msg 
)
private

Definition at line 286 of file open_cr_module.cpp.

void robotis_op::OpenCRModule::queueThread ( )
private

Definition at line 80 of file open_cr_module.cpp.

Member Data Documentation

const double robotis_op::OpenCRModule::ACCEL_FACTOR = 2.0 / 32768.0
private

Definition at line 52 of file open_cr_module.h.

ros::Time robotis_op::OpenCRModule::button_press_time_
private

Definition at line 72 of file open_cr_module.h.

ros::Publisher robotis_op::OpenCRModule::button_pub_
private

Definition at line 82 of file open_cr_module.h.

std::map<std::string, bool> robotis_op::OpenCRModule::buttons_
private

Definition at line 70 of file open_cr_module.h.

std::map<std::string, ros::Time> robotis_op::OpenCRModule::buttons_press_time_
private

Definition at line 71 of file open_cr_module.h.

int robotis_op::OpenCRModule::control_cycle_msec_
private

Definition at line 68 of file open_cr_module.h.

const bool robotis_op::OpenCRModule::DEBUG_PRINT
private

Definition at line 53 of file open_cr_module.h.

ros::Publisher robotis_op::OpenCRModule::dxl_power_msg_pub_
private

Definition at line 84 of file open_cr_module.h.

const double robotis_op::OpenCRModule::G_ACC = 9.80665
private

Definition at line 50 of file open_cr_module.h.

const double robotis_op::OpenCRModule::GYRO_FACTOR = 2000.0 / 32800.0
private

Definition at line 51 of file open_cr_module.h.

sensor_msgs::Imu robotis_op::OpenCRModule::imu_msg_
private

Definition at line 78 of file open_cr_module.h.

ros::Publisher robotis_op::OpenCRModule::imu_pub_
private

Definition at line 81 of file open_cr_module.h.

ros::Time robotis_op::OpenCRModule::last_msg_time_
private

Definition at line 73 of file open_cr_module.h.

double robotis_op::OpenCRModule::present_volt_
private

Definition at line 76 of file open_cr_module.h.

std::map<std::string, double> robotis_op::OpenCRModule::previous_result_
private

Definition at line 74 of file open_cr_module.h.

double robotis_op::OpenCRModule::previous_volt_
private

Definition at line 75 of file open_cr_module.h.

boost::thread robotis_op::OpenCRModule::queue_thread_
private

Definition at line 69 of file open_cr_module.h.

ros::Publisher robotis_op::OpenCRModule::status_msg_pub_
private

Definition at line 83 of file open_cr_module.h.


The documentation for this class was generated from the following files:


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